From def4173e683c3538388aabceeb08e5336c2bdadf Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Sun, 27 Feb 2011 03:07:31 -0500 Subject: libmaple: Refactor ADC routines ADC routines rewritten, support for ADC2, 3, added. Signed-off-by: Marti Bolivar --- wirish/boards.h | 307 ++++++++++++++++++++++++------------------------- wirish/wirish.c | 5 +- wirish/wirish_analog.c | 4 +- 3 files changed, 157 insertions(+), 159 deletions(-) (limited to 'wirish') diff --git a/wirish/boards.h b/wirish/boards.h index f8505ab..ac3a74d 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -51,18 +51,13 @@ enum { D92, D93, D94, D95, D96, D97, D98, D99, D100, D101, D102, D103, D104, D105, D106, D107, D108, D109, D110, D111, }; -/* Set of all possible analog pin names; not all boards have all these */ -enum { - ADC0, ADC1, ADC2, ADC3, ADC4, ADC5, ADC6, ADC7, ADC8, ADC9, ADC10, ADC11, - ADC12, ADC13, ADC14, ADC15, ADC16, ADC17, ADC18, ADC19, ADC20, }; - #define ADC_INVALID 0xFFFFFFFF /* Types used for the tables below */ typedef struct PinMapping { GPIO_Port *port; uint32 pin; - uint32 adc; + uint32 adc_channel; TimerCCR timer_ccr; uint32 exti_port; timer_dev_num timer_num; @@ -80,89 +75,89 @@ typedef struct PinMapping { static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D0/PA3 */ - {GPIOA_BASE, 3, ADC3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, + {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, /* D1/PA2 */ - {GPIOA_BASE, 2, ADC2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, + {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, /* D2/PA0 */ - {GPIOA_BASE, 0, ADC0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, + {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, /* D3/PA1 */ - {GPIOA_BASE, 1, ADC1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, + {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, /* D4/PB5 */ - {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D5/PB6 */ - {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, + {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, /* D6/PA8 */ - {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, + {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, /* D7/PA9 */ - {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, + {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, /* D8/PA10 */ - {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, + {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, /* D9/PB7 */ - {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, + {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, /* D10/PA4 */ - {GPIOA_BASE, 4, ADC4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D11/PA7 */ - {GPIOA_BASE, 7, ADC7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, + {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, /* D12/PA6 */ - {GPIOA_BASE, 6, ADC6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, + {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, /* D13/PA5 */ - {GPIOA_BASE, 5, ADC5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D14/PB8 */ - {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3}, + {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3}, /* Little header */ /* D15/PC0 */ - {GPIOC_BASE, 0, ADC10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D16/PC1 */ - {GPIOC_BASE, 1, ADC11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D17/PC2 */ - {GPIOC_BASE, 2, ADC12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D18/PC3 */ - {GPIOC_BASE, 3, ADC13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D19/PC4 */ - {GPIOC_BASE, 4, ADC14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D20/PC5 */ - {GPIOC_BASE, 5, ADC15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* External header */ /* D21/PC13 */ - {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D22/PC14 */ - {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D23/PC15 */ - {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D24/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D25/PD2 */ - {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D26/PC10 */ - {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D27/PB0 */ - {GPIOB_BASE, 0, ADC8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, + {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, /* D28/PB1 */ - {GPIOB_BASE, 1, ADC9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, + {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, /* D29/PB10 */ - {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D30/PB11 */ - {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D31/PB12 */ - {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D32/PB13 */ - {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D33/PB14 */ - {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D34/PB15 */ - {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D35/PC6 */ - {GPIOC_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D36/PC7 */ - {GPIOC_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D37/PC8 */ - {GPIOC_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D38/PC9 (BUT) */ - {GPIOC_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID} + {GPIOC_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID} }; #define BOARD_INIT do { \ @@ -182,212 +177,212 @@ typedef struct PinMapping { /* Top header */ /* D0/PB10 */ - {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D1/PB2 */ - {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D2/PB12 */ - {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D3/PB13 */ - {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D4/PB14 */ - {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D5/PB15 */ - {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D6/PC0 */ - {GPIOC_BASE, 0, ADC10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D7/PC1 */ - {GPIOC_BASE, 1, ADC11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D8/PC2 */ - {GPIOC_BASE, 2, ADC12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D9/PC3 */ - {GPIOC_BASE, 3, ADC13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D10/PC4 */ - {GPIOC_BASE, 4, ADC14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D11/PC5 */ - {GPIOC_BASE, 5, ADC15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D12/PC6 */ - {GPIOC_BASE, 6, ADC_INVALID, TIMER8_CH1_CCR, EXTI_CONFIG_PORTC, TIMER8, 1}, + {GPIOC_BASE, 6, ADC_INVALID, TIMER8_CH1_CCR, EXTI_CONFIG_PORTC, TIMER8, 1}, /* D13/PC7 */ - {GPIOC_BASE, 7, ADC_INVALID, TIMER8_CH2_CCR, EXTI_CONFIG_PORTC, TIMER8, 2}, + {GPIOC_BASE, 7, ADC_INVALID, TIMER8_CH2_CCR, EXTI_CONFIG_PORTC, TIMER8, 2}, /* D14/PC8 */ - {GPIOC_BASE, 8, ADC_INVALID, TIMER8_CH3_CCR, EXTI_CONFIG_PORTC, TIMER8, 3}, + {GPIOC_BASE, 8, ADC_INVALID, TIMER8_CH3_CCR, EXTI_CONFIG_PORTC, TIMER8, 3}, /* D15/PC9 */ - {GPIOC_BASE, 9, ADC_INVALID, TIMER8_CH4_CCR, EXTI_CONFIG_PORTC, TIMER8, 4}, + {GPIOC_BASE, 9, ADC_INVALID, TIMER8_CH4_CCR, EXTI_CONFIG_PORTC, TIMER8, 4}, /* D16/PC10 */ - {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D17/PC11 */ - {GPIOC_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D18/PC12 */ - {GPIOC_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D19/PC13 */ - {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D20/PC14 */ - {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D21/PC15 */ - {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, + {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D22/PA8 */ - {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, + {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, /* D23/PA9 */ - {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, + {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, /* D24/PA10 */ - {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, + {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, /* D25/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, + {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, /* Bottom header */ /* D26/PD2 */ - {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D27/PD3 */ - {GPIOD_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D28/PD6 */ - {GPIOD_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D29/PG11 */ - {GPIOG_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D30/PG12 */ - {GPIOG_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D31/PG13 */ - {GPIOG_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D32/PG14 */ - {GPIOG_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D33/PG8 */ - {GPIOG_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D34/PG7 */ - {GPIOG_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D35/PG6 */ - {GPIOG_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D36/PB5 */ - {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D37/PB6 */ - {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, + {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, /* D38/PB7 */ - {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, + {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, /* D39/PF6 */ - {GPIOF_BASE, 6, ADC4, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 6, 4, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D40/PF7 */ - {GPIOF_BASE, 7, ADC5, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 7, 5, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D41/PF8 */ - {GPIOF_BASE, 8, ADC6, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 8, 6, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D42/PF9 */ - {GPIOF_BASE, 9, ADC7, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 9, 7, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D43/PF10 */ - {GPIOF_BASE, 10, ADC8, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 10, 8, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D44/PF11 */ - {GPIOF_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D45/PB1 */ - {GPIOB_BASE, 1, ADC9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, + {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, /* D46/PB0 */ - {GPIOB_BASE, 0, ADC8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, + {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, /* D47/PA0 */ - {GPIOA_BASE, 0, ADC0, TIMER5_CH1_CCR, EXTI_CONFIG_PORTA, TIMER5, 1}, + {GPIOA_BASE, 0, 0, TIMER5_CH1_CCR, EXTI_CONFIG_PORTA, TIMER5, 1}, /* D48/PA1 */ - {GPIOA_BASE, 1, ADC1, TIMER5_CH2_CCR, EXTI_CONFIG_PORTA, TIMER5, 2}, /* FIXME (?) what to do about D48--D50 - also being TIMER2_CH[2,3,4]? */ + {GPIOA_BASE, 1, 1, TIMER5_CH2_CCR, EXTI_CONFIG_PORTA, TIMER5, 2}, /* FIXME (?) what to do about D48--D50 + also being TIMER2_CH[2,3,4]? */ /* D49/PA2 */ - {GPIOA_BASE, 2, ADC2, TIMER5_CH3_CCR, EXTI_CONFIG_PORTA, TIMER5, 3}, + {GPIOA_BASE, 2, 2, TIMER5_CH3_CCR, EXTI_CONFIG_PORTA, TIMER5, 3}, /* D50/PA3 */ - {GPIOA_BASE, 3, ADC3, TIMER5_CH4_CCR, EXTI_CONFIG_PORTA, TIMER5, 4}, + {GPIOA_BASE, 3, 3, TIMER5_CH4_CCR, EXTI_CONFIG_PORTA, TIMER5, 4}, /* D51/PA4 */ - {GPIOA_BASE, 4, ADC4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D52/PA5 */ - {GPIOA_BASE, 5, ADC5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D53/PA6 */ - {GPIOA_BASE, 6, ADC6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, + {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, /* D54/PA7 */ - {GPIOA_BASE, 7, ADC7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, + {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, /* Right (triple) header */ /* D55/PF0 */ - {GPIOF_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D56/PD11 */ - {GPIOD_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D57/PD14 */ - {GPIOD_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D58/PF1 */ - {GPIOF_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D59/PD12 */ - {GPIOD_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D60/PD15 */ - {GPIOD_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D61/PF2 */ - {GPIOF_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D62/PD13 */ - {GPIOD_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D63/PD0 */ - {GPIOD_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D64/PF3 */ - {GPIOF_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D65/PE3 */ - {GPIOE_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D66/PD1 */ - {GPIOD_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D67/PF4 */ - {GPIOF_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D68/PE4 */ - {GPIOE_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D69/PE7 */ - {GPIOE_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D70/PF5 */ - {GPIOF_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D71/PE5 */ - {GPIOE_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D72/PE8 */ - {GPIOE_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D73/PF12 */ - {GPIOF_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D74/PE6 */ - {GPIOE_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D75/PE9 */ - {GPIOE_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D76/PF13 */ - {GPIOF_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D77/PE10 */ - {GPIOE_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D78/PF14 */ - {GPIOF_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D79/PG9 */ - {GPIOG_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D80/PE11 */ - {GPIOE_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D81/PF15 */ - {GPIOF_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, + {GPIOF_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, /* D82/PG10 */ - {GPIOG_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D83/PE12 */ - {GPIOE_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D84/PG0 */ - {GPIOG_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D85/PD5 */ - {GPIOD_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D86/PE13 */ - {GPIOE_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D87/PG1 */ - {GPIOG_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D88/PD4 */ - {GPIOD_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D89/PE14 */ - {GPIOE_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D90/PG2 */ - {GPIOG_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D91/PE1 */ - {GPIOE_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D92/PE15 */ - {GPIOE_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D93/PG3 */ - {GPIOG_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D94/PE0 */ - {GPIOE_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, + {GPIOE_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, /* D95/PD8 */ - {GPIOD_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D96/PG4 */ - {GPIOG_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D97/PD9 */ - {GPIOD_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, + {GPIOD_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D98/PG5 */ - {GPIOG_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, + {GPIOG_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, /* D99/PD10 */ - {GPIOD_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID} + {GPIOD_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID} }; #define BOARD_INIT do { \ @@ -409,23 +404,23 @@ typedef struct PinMapping { /* D2/PB2 */ {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, /* D3/PB0 */ - {GPIOB_BASE, 0, ADC8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, + {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, /* D4/PA7 */ - {GPIOA_BASE, 7, ADC7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, + {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, /* D5/PA6 */ - {GPIOA_BASE, 6, ADC6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, + {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, /* D6/PA5 */ - {GPIOA_BASE, 5, ADC5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D7/PA4 */ - {GPIOA_BASE, 4, ADC4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, + {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, /* D8/PA3 */ - {GPIOA_BASE, 3, ADC3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, + {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, /* D9/PA2 */ - {GPIOA_BASE, 2, ADC2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, + {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, /* D10/PA1 */ - {GPIOA_BASE, 1, ADC1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, + {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, /* D11/PA0 */ - {GPIOA_BASE, 0, ADC0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, + {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, /* D12/PC15 */ {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D13/PC14 */ @@ -469,7 +464,7 @@ typedef struct PinMapping { /* D32/PB8 */ {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3}, /* D33/PB1 */ - {GPIOB_BASE, 1, ADC9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, + {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, }; /* since we want the Serial Wire/JTAG pins as GPIOs, disable both diff --git a/wirish/wirish.c b/wirish/wirish.c index aaae9d4..1ea4863 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -64,9 +64,12 @@ void init(void) { nvic_init(); systick_init(SYSTICK_RELOAD_VAL); gpio_init(); + /* Initialize the ADC for slow conversions, to allow for high impedance inputs. */ - adc_init(ADC_SMPR_55_5); + adc_init(ADC1, 0); + adc_set_sample_rate(ADC1->regs, ADC_SMPR_55_5); + timer_init(TIMER1, 1); timer_init(TIMER2, 1); timer_init(TIMER3, 1); diff --git a/wirish/wirish_analog.c b/wirish/wirish_analog.c index 3c63342..ba1290d 100644 --- a/wirish/wirish_analog.c +++ b/wirish/wirish_analog.c @@ -33,9 +33,9 @@ /* Assumes that the ADC has been initialized and that the pin is set * to ANALOG_INPUT */ uint32 analogRead(uint8 pin) { - if(PIN_MAP[pin].adc == ADC_INVALID) { + if(PIN_MAP[pin].adc_channel == ADC_INVALID) { return 0; } - return adc_read(PIN_MAP[pin].adc); + return adc_read(ADC1->regs, PIN_MAP[pin].adc_channel); } -- cgit v1.2.3 From c54f98951ea2827598babd4602e0f808b3ee311c Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Sun, 27 Feb 2011 06:38:53 -0500 Subject: Refactor DAC DAC header and source slightly cleaned up. Test on Maple Native prototype. Add flags parameter to allow selective enabling of channels. --- examples/test-dac.cpp | 6 +-- libmaple/dac.c | 89 ++++++++++++++++++++++++++++--------- libmaple/dac.h | 121 ++++++++++++++++++++++++++++++-------------------- wirish/wirish.c | 4 -- 4 files changed, 144 insertions(+), 76 deletions(-) (limited to 'wirish') diff --git a/examples/test-dac.cpp b/examples/test-dac.cpp index 3a699e2..62f40eb 100644 --- a/examples/test-dac.cpp +++ b/examples/test-dac.cpp @@ -16,7 +16,7 @@ void setup() { Serial1.println("**** Beginning DAC test"); Serial1.print("Init... "); - dac_init(); + dac_init(DAC_CH1 | DAC_CH2); Serial1.println("Done."); } @@ -29,8 +29,8 @@ void loop() { count = 0; } - dac_write(1, 2048); - dac_write(2, count); + dac_write_channel(1, 4095 - count); + dac_write_channel(2, count); } int main(void) { diff --git a/libmaple/dac.c b/libmaple/dac.c index 63a96ac..54b555b 100644 --- a/libmaple/dac.c +++ b/libmaple/dac.c @@ -23,7 +23,6 @@ *****************************************************************************/ #include "libmaple.h" -#include "rcc.h" #include "gpio.h" #include "dac.h" @@ -31,35 +30,81 @@ * @brief DAC peripheral routines. */ -/* This numbering follows the registers (1-indexed) */ -#define DAC_CH1 1 -#define DAC_CH2 2 +dac_dev dac = { + .regs = DAC_BASE, +}; +const dac_dev *DAC = &dac; -DAC_Map *dac = (DAC_Map*)(DAC_BASE); - -/* Sets up the DAC peripheral */ -void dac_init(void) { +/** + * @brief Initialize the digital to analog converter + * @param flags Flags: + * DAC_CH1: Enable channel 1 + * DAC_CH2: Enable channel 2 + * @sideeffect May set PA4 or PA5 to INPUT_ANALOG + */ +void dac_init(uint32 flags) { /* First turn on the clock */ rcc_clk_enable(RCC_DAC); + rcc_reset_dev(RCC_DAC); - /* Then setup ANALOG mode on PA4 and PA5 */ - gpio_set_mode(GPIOA_BASE, 4, CNF_INPUT_ANALOG); - gpio_set_mode(GPIOA_BASE, 5, CNF_INPUT_ANALOG); + if (flags & DAC_CH1) { + dac_enable_channel(1); + } - /* Then do register stuff. Default does no triggering, and - * buffered output, so all good. */ - dac->CR = DAC_CR_EN1 | DAC_CR_EN2; + if (flags & DAC_CH2) { + dac_enable_channel(2); + } } -void dac_write(uint8 chan, uint16 val) { - switch(chan) { - case DAC_CH1: - dac->DHR12R1 = 0x0FFF & val; +/** + * @brief Write a 12-bit value to the DAC to output + * @param channel channel to select (1 or 2) + * @param val value to write + */ +void dac_write_channel(uint8 channel, uint16 val) { + switch(channel) { + case 1: + DAC->regs->DHR12R1 = DAC_DHR12R1_DACC1DHR & val; + break; + case 2: + DAC->regs->DHR12R2 = DAC_DHR12R2_DACC2DHR & val; + break; + } +} + +/** + * @brief Enable a DAC channel + * @param channel channel to enable, either 1 or 2 + * @sideeffect May change pin mode of PA4 or PA5 + */ +void dac_enable_channel(uint8 channel) { + /* + * Setup ANALOG mode on PA4 and PA5. This mapping is consistent across + * all STM32 chips with a DAC. See RM008 12.2. + */ + switch (channel) { + case 1: + gpio_set_mode(GPIOA_BASE, 4, GPIO_MODE_INPUT_ANALOG); + DAC->regs->CR |= DAC_CR_EN1; + break; + case 2: + gpio_set_mode(GPIOA_BASE, 5, GPIO_MODE_INPUT_ANALOG); + DAC->regs->CR |= DAC_CR_EN2; + break; + } +} + +/** + * @brief Disable a DAC channel + * @param channel channel to disable, either 1 or 2 + */ +void dac_disable_channel(uint8 channel) { + switch (channel) { + case 1: + DAC->regs->CR &= ~DAC_CR_EN1; break; - case DAC_CH2: - dac->DHR12R2 = 0x0FFF & val; + case 2: + DAC->regs->CR &= ~DAC_CR_EN2; break; - default: - ASSERT(0); // can't happen } } diff --git a/libmaple/dac.h b/libmaple/dac.h index 340a49a..3148809 100644 --- a/libmaple/dac.h +++ b/libmaple/dac.h @@ -22,88 +22,115 @@ * THE SOFTWARE. *****************************************************************************/ -/* - * See ../notes/dac.txt for more info - */ - /** * @file dac.h + * @brief Digital to analog converter header file + * See notes/dac.txt for more info */ #ifndef _DAC_H_ #define _DAC_H_ +#include "rcc.h" + #ifdef __cplusplus extern "C"{ #endif -#define DAC_BASE 0x40007400 - -typedef struct { - volatile uint32 CR; - volatile uint32 SWTRIGR; - volatile uint32 DHR12R1; - volatile uint32 DHR12L1; - volatile uint32 DHR8R1; - volatile uint32 DHR12R2; - volatile uint32 DHR12L2; - volatile uint32 DHR8R2; - volatile uint32 DHR12RD; - volatile uint32 DHR12LD; - volatile uint32 DHR8RD; - volatile uint32 DOR1; - volatile uint32 DOR2; -} DAC_Map; - -/* There's only one DAC, so expose it. */ -extern DAC_Map *dac; - -// And here are the register bit ranges -#define DAC_CR_EN1 BIT(0) -#define DAC_CR_BOFF1 BIT(1) -#define DAC_CR_TEN1 BIT(2) -#define DAC_CR_TSEL1 (BIT(3) | BIT(4) | BIT(5)) -#define DAC_CR_WAVE1 (BIT(6) | BIT(7)) -#define DAC_CR_MAMP1 (BIT(8) | BIT(9) | BIT(10) | BIT(11)) -#define DAC_CR_DMAEN1 BIT(12) -#define DAC_CR_EN2 BIT(16) -#define DAC_CR_BOFF2 BIT(17) -#define DAC_CR_TEN2 BIT(18) -#define DAC_CR_TSEL2 (BIT(19) | BIT(20) | BIT(21)) -#define DAC_CR_WAVE2 (BIT(22) | BIT(23)) -#define DAC_CR_MAMP2 (BIT(24) | BIT(25) | BIT(26) | BIT(27)) -#define DAC_CR_DMAEN2 BIT(28) - -#define DAC_SWTRIGR_SWTRIG1 BIT(0) -#define DAC_SWTRIGR_SWTRIG2 BIT(1) +typedef struct dac_reg_map { + __io uint32 CR; ///< Control register + __io uint32 SWTRIGR; ///< Software trigger register + __io uint32 DHR12R1; ///< Channel 1 12-bit right aligned data holding register + __io uint32 DHR12L1; ///< Channel 1 12-bit left aligned data holding register + __io uint32 DHR8R1; ///< Channel 1 8-bit left aligned data holding register + __io uint32 DHR12R2; ///< Channel 2 12-bit right aligned data holding register + __io uint32 DHR12L2; ///< Channel 2 12-bit left aligned data holding register + __io uint32 DHR8R2; ///< Channel 2 8-bit left aligned data holding register + __io uint32 DHR12RD; ///< Dual DAC 12-bit right aligned data holding register + __io uint32 DHR12LD; ///< Dual DAC 12-bit left aligned data holding register + __io uint32 DHR8RD; ///< Dual DAC 8-bit left aligned data holding register + __io uint32 DOR1; ///< Channel 1 data output register + __io uint32 DOR2; ///< Channel 2 data output register +} dac_reg_map; + +typedef struct dac_dev { + dac_reg_map *regs; +} dac_dev; + +extern const dac_dev *DAC; +/* + * DAC peripheral base address + */ +#define DAC_BASE ((dac_reg_map*)0x40007400) + +/* + * Register bit definitions and masks + */ + +/* Control register */ +#define DAC_CR_EN1 BIT(0) // Channel 1 enable +#define DAC_CR_BOFF1 BIT(1) // Channel 1 output buffer disable +#define DAC_CR_TEN1 BIT(2) // Channel 1 trigger enable +#define DAC_CR_TSEL1 (0x7 << 3) // Channel 1 trigger selection +#define DAC_CR_WAVE1 (0x3 << 6) // Channel 1 noise/triangle wave generationg enable +#define DAC_CR_MAMP1 (0xF << 8) // Channel 1 mask/amplitude selector +#define DAC_CR_DMAEN1 BIT(12) // Channel 1 DMA enable +#define DAC_CR_EN2 BIT(16) // Channel 2 enable +#define DAC_CR_BOFF2 BIT(17) // Channel 2 output buffer disable +#define DAC_CR_TEN2 BIT(18) // Channel 2 trigger enable +#define DAC_CR_TSEL2 (0x7 << 19) // Channel 2 trigger selection +#define DAC_CR_WAVE2 (0x3 << 22) // Channel 2 noise/triangle wave generationg enable +#define DAC_CR_MAMP2 (0xF << 24) // Channel 2 mask/amplitude selector +#define DAC_CR_DMAEN2 BIT(28) // Channel 2 DMA enable + +/* Software trigger register */ +#define DAC_SWTRIGR_SWTRIG1 BIT(0) // Channel 1 software trigger +#define DAC_SWTRIGR_SWTRIG2 BIT(1) // Channel 2 software trigger + +/* Channel 1 12-bit right aligned data holding register */ #define DAC_DHR12R1_DACC1DHR 0x00000FFF +/* Channel 1 12-bit left aligned data holding register */ #define DAC_DHR12L1_DACC1DHR 0x0000FFF0 +/* Channel 1 8-bit left aligned data holding register */ #define DAC_DHR8R1_DACC1DHR 0x000000FF +/* Channel 2 12-bit right aligned data holding register */ #define DAC_DHR12R2_DACC2DHR 0x00000FFF +/* Channel 2 12-bit left aligned data holding register */ #define DAC_DHR12L2_DACC2DHR 0x0000FFF0 +/* Channel 2 8-bit left aligned data holding register */ #define DAC_DHR8R2_DACC2DHR 0x000000FF +/* Dual DAC 12-bit right aligned data holding register */ #define DAC_DHR12RD_DACC1DHR 0x00000FFF #define DAC_DHR12RD_DACC2DHR 0x0FFF0000 +/* Dual DAC 12-bit left aligned data holding register */ #define DAC_DHR12LD_DACC1DHR 0x0000FFF0 #define DAC_DHR12LD_DACC2DHR 0xFFF00000 +/* Dual DAC 8-bit left aligned data holding register */ #define DAC_DHR8RD_DACC1DHR 0x000000FF #define DAC_DHR8RD_DACC2DHR 0x0000FF00 -#define DAC_DOR1 0x00000FFF +/* Channel 1 data output register */ +#define DAC_DOR1_DACC1DOR 0x00000FFF + +/* Channel 1 data output register */ +#define DAC_DOR2_DACC2DOR 0x00000FFF -#define DAC_DOR2 0x00000FFF +#define DAC_CH1 0x1 +#define DAC_CH2 0x2 +void dac_init(uint32 flags); -void dac_init(void); -void dac_write(uint8 chan, uint16 val); +void dac_write_channel(uint8 channel, uint16 val); +void dac_enable_channel(uint8 channel); +void dac_disable_channel(uint8 channel); #ifdef __cplusplus } // extern "C" diff --git a/wirish/wirish.c b/wirish/wirish.c index 1ea4863..a74e297 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -51,10 +51,6 @@ void init(void) { fsmc_native_sram_init(); #endif -#if NR_DAC_PINS > 0 - dac_init(); -#endif - /* initialize clocks */ rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); -- cgit v1.2.3 From e05a9ef311ad2c690a0d9176004a167effb537c8 Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Sun, 27 Feb 2011 07:37:19 -0500 Subject: Refactor ADC: Pass device pointer instead of register map --- libmaple/adc.c | 42 ++++++++++++++++++++++-------------------- libmaple/adc.h | 34 ++++++++++++++++++++-------------- wirish/wirish.c | 2 +- wirish/wirish_analog.c | 2 +- 4 files changed, 44 insertions(+), 36 deletions(-) (limited to 'wirish') diff --git a/libmaple/adc.c b/libmaple/adc.c index adadc63..17d63b8 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -38,26 +38,26 @@ #include "adc.h" adc_dev adc1 = { - .regs = (adc_reg_map*)ADC1_BASE, + .regs = ADC1_BASE, .clk_id = RCC_ADC1 }; const adc_dev *ADC1 = &adc1; adc_dev adc2 = { - .regs = (adc_reg_map*)ADC2_BASE, + .regs = ADC2_BASE, .clk_id = RCC_ADC2 }; const adc_dev *ADC2 = &adc2; #if NR_ADCS >= 3 adc_dev adc3 = { - .regs = (adc_reg_map*)ADC3_BASE, + .regs = ADC3_BASE, .clk_id = RCC_ADC3 }; const adc_dev *ADC3 = &adc3; #endif -static void adc_calibrate(adc_reg_map *regs); +static void adc_calibrate(const adc_dev *dev); /** * @brief Initialize an ADC peripheral. Only supports software triggered @@ -72,39 +72,40 @@ void adc_init(const adc_dev *dev, uint32 flags) { rcc_reset_dev(dev->clk_id); /* Software triggers conversions, conversion on external events */ - adc_set_extsel(dev->regs, 7); - adc_set_exttrig(dev->regs, 1); + adc_set_extsel(dev, 7); + adc_set_exttrig(dev, 1); /* Enable the ADC */ - adc_enable(dev->regs); + adc_enable(dev); /* Calibrate ADC */ - adc_calibrate(dev->regs); + adc_calibrate(dev); } /** * @brief Set external event select for regular group - * @param regs adc register map + * @param dev adc device * @param trigger event to select. See ADC_CR2 EXTSEL[2:0] bits. */ -void adc_set_extsel(adc_reg_map *regs, uint8 trigger) { - uint32 cr2 = regs->CR2; +void adc_set_extsel(const adc_dev *dev, uint8 trigger) { + uint32 cr2 = dev->regs->CR2; cr2 &= ~ADC_CR2_EXTSEL; cr2 |= (trigger & 0x7) << 17; - regs->CR2 = cr2; + dev->regs->CR2 = cr2; } /** * @brief Turn the given sample rate into values for ADC_SMPRx. Don't * call this during conversion. - * @param regs adc register map + * @param dev adc device * @param smp_rate sample rate to set * @see adc_smp_rate */ -void adc_set_sample_rate(adc_reg_map *regs, adc_smp_rate smp_rate) { +void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { uint32 adc_smpr1_val = 0, adc_smpr2_val = 0; int i; + for (i = 0; i < 10; i++) { if (i < 8) { /* ADC_SMPR1 determines sample time for channels [10,17] */ @@ -113,17 +114,18 @@ void adc_set_sample_rate(adc_reg_map *regs, adc_smp_rate smp_rate) { /* ADC_SMPR2 determines sample time for channels [0,9] */ adc_smpr2_val |= smp_rate << (i * 3); } - regs->SMPR1 = adc_smpr1_val; - regs->SMPR2 = adc_smpr2_val; + + dev->regs->SMPR1 = adc_smpr1_val; + dev->regs->SMPR2 = adc_smpr2_val; } /** * @brief Calibrate an ADC peripheral - * @param regs adc register map + * @param dev adc device */ -static void adc_calibrate(adc_reg_map *regs) { - __io uint32 *rstcal_bit = (__io uint32*)BITBAND_PERI(&(regs->CR2), 3); - __io uint32 *cal_bit = (__io uint32*)BITBAND_PERI(&(regs->CR2), 2); +static void adc_calibrate(const adc_dev *dev) { + __io uint32 *rstcal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 3); + __io uint32 *cal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 2); *rstcal_bit = 1; while (*rstcal_bit) diff --git a/libmaple/adc.h b/libmaple/adc.h index 4997d14..ab6e643 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -75,9 +75,9 @@ extern const adc_dev *ADC3; /* * ADC peripheral base addresses */ -#define ADC1_BASE 0x40012400 -#define ADC2_BASE 0x40012800 -#define ADC3_BASE 0x40013C00 +#define ADC1_BASE ((adc_reg_map*)0x40012400) +#define ADC2_BASE ((adc_reg_map*)0x40012800) +#define ADC3_BASE ((adc_reg_map*)0x40013C00) /* * Register bit definitions @@ -120,7 +120,7 @@ extern const adc_dev *ADC3; #define ADC_CR2_TSEREFE BIT(23) void adc_init(const adc_dev *dev, uint32 flags); -void adc_set_extsel(adc_reg_map *regs, uint8 trigger); +void adc_set_extsel(const adc_dev *dev, uint8 trigger); /** ADC per-sample conversion times, in ADC clock cycles */ typedef enum { @@ -134,7 +134,7 @@ typedef enum { ADC_SMPR_239_5 ///< 239.5 ADC cycles } adc_smp_rate; -void adc_set_sample_rate(adc_reg_map *regs, adc_smp_rate smp_rate); +void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); /** * @brief Perform a single synchronous software triggered conversion on a @@ -143,7 +143,9 @@ void adc_set_sample_rate(adc_reg_map *regs, adc_smp_rate smp_rate); * @param channel channel to convert * @return conversion result */ -static inline uint32 adc_read(adc_reg_map *regs, uint8 channel) { +static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { + adc_reg_map *regs = dev->regs; + /* Set target channel */ regs->SQR3 = channel; @@ -159,34 +161,38 @@ static inline uint32 adc_read(adc_reg_map *regs, uint8 channel) { /** * @brief Set external trigger conversion mode event for regular channels - * @param regs adc register map + * @param dev adc device * @param enable if 1, conversion on external events is enabled, 0 to disable */ -static inline void adc_set_exttrig(adc_reg_map *regs, uint8 enable) { - __write(BITBAND_PERI(&(regs->CR2), 20), enable); +static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { + __write(BITBAND_PERI(&(dev->regs->CR2), 20), enable); } /** * @brief Enable an adc peripheral * @param regs register map of peripheral to enable */ -static inline void adc_enable(adc_reg_map *regs) { - __write(BITBAND_PERI(&(regs->CR2), 0), 1); +static inline void adc_enable(const adc_dev *dev) { + __write(BITBAND_PERI(&(dev->regs->CR2), 0), 1); } /** * @brief Disable an adc peripheral * @param regs register map of peripheral to disable */ -static inline void adc_disable(adc_reg_map *regs) { - __write(BITBAND_PERI(&(regs->CR2), 0), 0); +static inline void adc_disable(const adc_dev *dev) { + __write(BITBAND_PERI(&(dev->regs->CR2), 0), 0); } /** * @brief Disable all ADCs */ static inline void adc_disable_all(void) { - adc_disable(ADC1->regs); + adc_disable(ADC1); + adc_disable(ADC2); +#if NR_ADCS >= 3 + adc_disable(ADC3); +#endif } #ifdef __cplusplus diff --git a/wirish/wirish.c b/wirish/wirish.c index a74e297..c5dec22 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -64,7 +64,7 @@ void init(void) { /* Initialize the ADC for slow conversions, to allow for high impedance inputs. */ adc_init(ADC1, 0); - adc_set_sample_rate(ADC1->regs, ADC_SMPR_55_5); + adc_set_sample_rate(ADC1, ADC_SMPR_55_5); timer_init(TIMER1, 1); timer_init(TIMER2, 1); diff --git a/wirish/wirish_analog.c b/wirish/wirish_analog.c index ba1290d..a658184 100644 --- a/wirish/wirish_analog.c +++ b/wirish/wirish_analog.c @@ -37,5 +37,5 @@ uint32 analogRead(uint8 pin) { return 0; } - return adc_read(ADC1->regs, PIN_MAP[pin].adc_channel); + return adc_read(ADC1, PIN_MAP[pin].adc_channel); } -- cgit v1.2.3 From 4e90248a2e81ec7bd8d3cfa858cef4a045cc1003 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Sun, 27 Feb 2011 11:42:56 -0500 Subject: Cleaned out libmaple.h; this had wide-ranging implications. Many of the #defines in libmaple.h were board-specific, not MCU-specific. Most of these were only used by code under libmaple/usb/. These were moved into usb_config.h, and are clearly marked as being terrible hacks. I'm going to treat the USB stack as a black box that we'll deal with later. Further, instead of having a variety of #defines like "How many USARTS do I have?", we decide that based on the density of the chip. This is determined by testing for STM32_MEDIUM_DENSITY or STM32_HIGH_DENSITY defines. libmaple currently doesn't support low-density chips, so that suffices. The Makefile will set these automatically based on the MCU. Other offending #defines are ERROR_LED_PORT and ERROR_LED_PIN; these were made optional, but they're set in the Makefile as a hack to keep things working. --- Makefile | 37 ++++++++-- docs/source/language.rst | 57 ++++++++-------- examples/test-bkp.cpp | 38 ++++++----- examples/test-session.cpp | 3 +- libmaple/adc.c | 2 +- libmaple/adc.h | 4 +- libmaple/bkp.c | 12 ++-- libmaple/bkp.h | 8 ++- libmaple/libmaple.h | 163 +++++++-------------------------------------- libmaple/libmaple_types.h | 2 - libmaple/timers.c | 10 +-- libmaple/timers.h | 6 +- libmaple/usart.c | 12 ++-- libmaple/usart.h | 2 + libmaple/usb/descriptors.c | 73 +++++++++++--------- libmaple/usb/usb_config.h | 76 +++++++++++++++++++-- libmaple/util.c | 23 +++++++ libmaple/util.h | 33 ++++++--- wirish/HardwareTimer.cpp | 4 +- wirish/HardwareTimer.h | 2 +- wirish/boards.h | 18 +++-- wirish/ext_interrupts.h | 4 +- wirish/wirish.c | 4 +- 23 files changed, 308 insertions(+), 285 deletions(-) (limited to 'wirish') diff --git a/Makefile b/Makefile index a709696..149f54a 100644 --- a/Makefile +++ b/Makefile @@ -9,17 +9,27 @@ VENDOR_ID := 1EAF PRODUCT_ID := 0003 # Guess the MCU based on the BOARD (can be overridden ) +# FIXME the error LED config needs to be in wirish/ instead ifeq ($(BOARD), maple) MCU := STM32F103RB PRODUCT_ID := 0003 + ERROR_LED_PORT := GPIOA_BASE + ERROR_LED_PIN := 5 + DENSITY := STM32_MEDIUM_DENSITY endif ifeq ($(BOARD), maple_native) MCU := STM32F103ZE PRODUCT_ID := 0003 + ERROR_LED_PORT := GPIOC_BASE + ERROR_LED_PIN := 15 + DENSITY := STM32_HIGH_DENSITY endif ifeq ($(BOARD), maple_mini) MCU := STM32F103CB PRODUCT_ID := 0003 + ERROR_LED_PORT := GPIOB_BASE + ERROR_LED_PIN := 1 + DENSITY := STM32_MEDIUM_DENSITY endif # Useful paths @@ -32,13 +42,26 @@ BUILD_PATH = build LIBMAPLE_PATH := $(SRCROOT)/libmaple SUPPORT_PATH := $(SRCROOT)/support -# Useful variables -GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m -nostdlib \ - -ffunction-sections -fdata-sections -Wl,--gc-sections \ - -DBOARD_$(BOARD) -DMCU_$(MCU) -GLOBAL_CXXFLAGS := -fno-rtti -fno-exceptions -Wall -DBOARD_$(BOARD) -DMCU_$(MCU) -GLOBAL_ASFLAGS := -mcpu=cortex-m3 -march=armv7-m -mthumb -DBOARD_$(BOARD) \ - -DMCU_$(MCU) -x assembler-with-cpp +# Compilation flags. +# FIXME remove the ERROR_LED config +GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m \ + -nostdlib \ + -ffunction-sections -fdata-sections -Wl,--gc-sections \ + -DBOARD_$(BOARD) -DMCU_$(MCU) \ + -DERROR_LED_PORT=$(ERROR_LED_PORT) \ + -DERROR_LED_PIN=$(ERROR_LED_PIN) \ + -D$(DENSITY) +GLOBAL_CXXFLAGS := -fno-rtti -fno-exceptions -Wall \ + -DBOARD_$(BOARD) -DMCU_$(MCU) \ + -DERROR_LED_PORT=$(ERROR_LED_PORT) \ + -DERROR_LED_PIN=$(ERROR_LED_PIN) \ + -D$(DENSITY) +GLOBAL_ASFLAGS := -mcpu=cortex-m3 -march=armv7-m -mthumb \ + -x assembler-with-cpp \ + -DBOARD_$(BOARD) -DMCU_$(MCU) \ + -DERROR_LED_PORT=$(ERROR_LED_PORT) \ + -DERROR_LED_PIN=$(ERROR_LED_PIN) \ + -D$(DENSITY) LDDIR := $(SUPPORT_PATH)/ld LDFLAGS = -T$(LDDIR)/$(LDSCRIPT) -L$(LDDIR) \ diff --git a/docs/source/language.rst b/docs/source/language.rst index 2ebe03c..b2f4650 100644 --- a/docs/source/language.rst +++ b/docs/source/language.rst @@ -17,36 +17,6 @@ language and C++ may wish to skip to the .. contents:: Contents :local: -Unique Maple Additions ----------------------- - -.. _language-assert: - -``ASSERT(...)`` - The ``ASSERT()`` function can be very useful for basic program - debugging. The function accepts a boolean; for example:: - - ASSERT(state == WAIT); - - zero is false and any other number is true. If the boolean is true - the assertion passes and the program continues as usual. If it is - false, the assertion fails: the program is halted, debug - information is printed to USART2, and the status LED begins to - throb in intensity (it's noticeably different from blinking). The - debug information is printed at 9600 baud and consists of the - filename and line number where the particular assertion failed. - - Including assertions in a program increases the program size. When - using libmaple **from the command line only**, they can be - disabled by making the definition :: - - #define DEBUG_LEVEL DEBUG_NONE - - before including either wirish.h or libmaple.h. In this case, all - assertions will pass without any lost clock cycles. Note that - this will **not work in the IDE**; even with this definition, - assertions will still be enabled. - .. _language-lang-docs: Maple Language Reference @@ -217,6 +187,33 @@ A more exhaustive index is available at the :ref:`language-index`. | | | | +--------------------------------------------+----------------------------------------------+---------------------------------------------------+ +``ASSERT(...)`` +--------------- + +The ``ASSERT()`` function can be very useful for basic program +debugging. The function accepts a boolean; for example:: + + ASSERT(state == WAIT); + +Zero is false and any other number is true. If the boolean is true, the +assertion passes and the program continues as usual. If it is false, +the assertion fails: the program is halted, debug information is +printed to USART2, and the status LED begins to throb in intensity +(it's noticeably different from blinking). The debug information is +printed at 9600 baud and consists of the filename and line number +where the particular assertion failed. + +Including assertions in a program increases the program size. When +using libmaple **from the command line only**, they can be disabled by +making the definition :: + + #define DEBUG_LEVEL DEBUG_NONE + +before including either wirish.h or libmaple.h. In this case, all +assertions will pass without any lost clock cycles. Note that this +will **not work in the IDE**; even with this definition, assertions +will still be enabled. + .. _language-missing-features: Missing Arduino Features diff --git a/examples/test-bkp.cpp b/examples/test-bkp.cpp index 27f87bd..d0aa564 100644 --- a/examples/test-bkp.cpp +++ b/examples/test-bkp.cpp @@ -7,59 +7,61 @@ void print_bkp_contents(); void write_to_bkp(uint16 val); +#define comm Serial2 + void setup() { pinMode(BOARD_BUTTON_PIN, INPUT); - Serial2.begin(9600); - Serial2.println("*** Beginning BKP test"); + comm.begin(9600); + comm.println("*** Beginning BKP test"); - Serial2.println("Init..."); + comm.println("Init..."); bkp_init(); - Serial2.println("Done."); + comm.println("Done."); print_bkp_contents(); write_to_bkp(10); print_bkp_contents(); - Serial2.println("Enabling backup writes."); + comm.println("Enabling backup writes."); bkp_enable_writes(); write_to_bkp(20); print_bkp_contents(); - Serial2.println("Disabling backup writes."); + comm.println("Disabling backup writes."); bkp_disable_writes(); write_to_bkp(30); print_bkp_contents(); - Serial2.println("Done testing backup registers; press button to enable " + comm.println("Done testing backup registers; press button to enable " "independent watchdog (in order to cause a reset)."); waitForButtonPress(0); iwdg_init(IWDG_PRE_4, 1); - Serial2.println(); + comm.println(); } void loop() { } void print_bkp_contents() { - Serial2.println("Backup data register contents:"); + comm.println("Backup data register contents:"); char buf[100]; - for (int i = 1; i <= NR_BKP_REGS; i++) { + for (int i = 1; i <= BKP_NR_DATA_REGS; i++) { snprintf(buf, sizeof buf, "DR%d: %d ", i, bkp_read(i)); - Serial2.print(buf); - if (i % 5 == 0) Serial2.println(); + comm.print(buf); + if (i % 5 == 0) comm.println(); } - Serial2.println(); + comm.println(); } void write_to_bkp(uint16 val) { - Serial2.print("Attempting to write "); - Serial2.print(val); - Serial2.println(" to backup registers..."); - for (int i = 1; i <= NR_BKP_REGS; i++) { + comm.print("Attempting to write "); + comm.print(val); + comm.println(" to backup registers..."); + for (int i = 1; i <= BKP_NR_DATA_REGS; i++) { bkp_write(i, val); } - Serial2.println("Done."); + comm.println("Done."); } __attribute__((constructor)) void premain() { diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 86bab6d..72d64d6 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -614,9 +614,8 @@ void init_all_timers(uint16 prescale) { timer_init(TIMER1, prescale); timer_init(TIMER2, prescale); timer_init(TIMER3, prescale); -#if NR_TIMERS >= 4 timer_init(TIMER4, prescale); -#elif NR_TIMERS >= 8 // TODO test this on maple native +#ifdef STM32_HIGH_DENSITY timer_init(TIMER5, prescale); timer_init(TIMER6, prescale); timer_init(TIMER7, prescale); diff --git a/libmaple/adc.c b/libmaple/adc.c index 17d63b8..cd71118 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -49,7 +49,7 @@ adc_dev adc2 = { }; const adc_dev *ADC2 = &adc2; -#if NR_ADCS >= 3 +#ifdef STM32_HIGH_DENSITY adc_dev adc3 = { .regs = ADC3_BASE, .clk_id = RCC_ADC3 diff --git a/libmaple/adc.h b/libmaple/adc.h index ab6e643..ac386fb 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -68,7 +68,7 @@ typedef struct adc_dev { extern const adc_dev *ADC1; extern const adc_dev *ADC2; -#if NR_ADCS >= 3 +#ifdef STM32_HIGH_DENSITY extern const adc_dev *ADC3; #endif @@ -190,7 +190,7 @@ static inline void adc_disable(const adc_dev *dev) { static inline void adc_disable_all(void) { adc_disable(ADC1); adc_disable(ADC2); -#if NR_ADCS >= 3 +#ifdef STM32_HIGH_DENSITY adc_disable(ADC3); #endif } diff --git a/libmaple/bkp.c b/libmaple/bkp.c index ac9aeae..ed107d8 100644 --- a/libmaple/bkp.c +++ b/libmaple/bkp.c @@ -69,7 +69,8 @@ void bkp_disable_writes(void) { /** * Read a value from given backup data register. - * @param reg Data register to read, from 1 to NR_BKP_REGS (10 on Maple). + * @param reg Data register to read, from 1 to BKP_NR_DATA_REGS (10 on + * medium-density devices, 42 on high-density devices). */ uint16 bkp_read(uint8 reg) { __io uint32* dr = data_register(reg); @@ -85,7 +86,8 @@ uint16 bkp_read(uint8 reg) { * * Write access to backup registers must be enabled. * - * @param reg Data register to write, from 1 to NR_BKP_REGS (10 on Maple). + * @param reg Data register to write, from 1 to BKP_NR_DATA_REGS (10 + * on medium-density devices, 42 on high-density devices). * @param val Value to write into the register. * @see bkp_enable_writes() */ @@ -101,16 +103,16 @@ void bkp_write(uint8 reg, uint16 val) { /* * Data register memory layout is not contiguous. It's split up from * 1--NR_LOW_DRS, beginning at BKP_BASE->DR1, through to - * (NR_LOW_DRS+1)--NR_BKP_REGS, beginning at BKP_BASE->DR10. + * (NR_LOW_DRS+1)--BKP_NR_DATA_REGS, beginning at BKP_BASE->DR11. */ #define NR_LOW_DRS 10 static inline __io uint32* data_register(uint8 reg) { - if (reg < 1 || reg > NR_BKP_REGS) { + if (reg < 1 || reg > BKP_NR_DATA_REGS) { return 0; } -#if NR_BKP_REGS == NR_LOW_DRS +#if BKP_NR_DATA_REGS == NR_LOW_DRS return (uint32*)BKP_BASE + reg; #else if (reg <= NR_LOW_DRS) { diff --git a/libmaple/bkp.h b/libmaple/bkp.h index ce8e6c7..96ef8d2 100644 --- a/libmaple/bkp.h +++ b/libmaple/bkp.h @@ -38,6 +38,12 @@ extern "C" { #endif +#if defined(STM32_MEDIUM_DENSITY) +#define BKP_NR_DATA_REGS 10 +#elif defined(STM32_HIGH_DENSITY) +#define BKP_NR_DATA_REGS 42 +#endif + typedef struct bkp_reg_map { const uint32 RESERVED1; __io uint32 DR1; ///< Data register 1 @@ -53,7 +59,7 @@ typedef struct bkp_reg_map { __io uint32 RTCCR; ///< RTC control register __io uint32 CR; ///< Control register __io uint32 CSR; ///< Control and status register -#if NR_BKP_REGS > 10 +#ifdef STM32_HIGH_DENSITY const uint32 RESERVED2; const uint32 RESERVED3; __io uint32 DR11; ///< Data register 11 diff --git a/libmaple/libmaple.h b/libmaple/libmaple.h index 4f9a71a..6b75c96 100644 --- a/libmaple/libmaple.h +++ b/libmaple/libmaple.h @@ -24,164 +24,50 @@ /** * @file libmaple.h - * - * @brief general include file for libmaple + * @brief General include file for libmaple */ #ifndef _LIBMAPLE_H_ #define _LIBMAPLE_H_ #include "libmaple_types.h" +#include "util.h" -/* General configuration */ -#define DEBUG_NONE 0 -#define DEBUG_FAULT 1 -#define DEBUG_ALL 2 - -#ifndef DEBUG_LEVEL -#define DEBUG_LEVEL DEBUG_ALL -#endif +/* + * Where to put usercode, based on space reserved for bootloader. + * + * FIXME this has no business being here + */ +#define USER_ADDR_ROM 0x08005000 +#define USER_ADDR_RAM 0x20000C00 +#define STACK_TOP 0x20000800 /* MCU-specific configuration */ #if defined(MCU_STM32F103RB) /* e.g., LeafLabs Maple */ /* Number of GPIO ports (GPIOA, GPIOB, etc.) */ - #define NR_GPIO_PORTS 4 - - /* Total number of GPIO pins */ - #define NR_GPIO_PINS 39 - - /* Number of 16-bit backup registers */ - #define NR_BKP_REGS 10 - - /* Number of timer devices ports, definitely used */ - #define NR_TIMERS 4 - - /* Number of USART ports */ - #define NR_USART 3 - - /* Number of ADCs */ - #define NR_ADCS 2 - - /* Has an FSMC bus? */ - #define NR_FSMC 0 - - /* Has a DAC? */ - #define NR_DAC_PINS 0 - - /* USB Identifier numbers */ - /* Descriptor strings must be modified by hand in - usb/descriptors.c for now */ - #define VCOM_ID_VENDOR 0x1EAF - #define VCOM_ID_PRODUCT 0x0004 - #define USB_DISC_BANK GPIOC_BASE - #define USB_DISC_PIN 12 - #define USB_CONFIG_MAX_POWER (100 >> 1) - #define RESET_DELAY (100) - - /* Where to put usercode (based on space reserved for bootloader) */ - #define USER_ADDR_ROM 0x08005000 - #define USER_ADDR_RAM 0x20000C00 - #define STACK_TOP 0x20000800 - - /* Debug port settings (from ASSERT) */ - #define ERROR_LED_PORT GPIOB_BASE - #define ERROR_LED_PIN 12 - #define ERROR_USART_NUM USART2 - #define ERROR_USART_BAUD 9600 - #define ERROR_TX_PORT GPIOA_BASE - #define ERROR_TX_PIN 2 - - /* Just in case, most boards have at least some memory */ - #ifndef RAMSIZE - # define RAMSIZE (caddr_t)0x50000 - #endif - - /* Bitbanded Memory sections */ - #define BITBAND_SRAM_REF 0x20000000 - #define BITBAND_SRAM_BASE 0x22000000 - #define BITBAND_PERI_REF 0x40000000 - #define BITBAND_PERI_BASE 0x42000000 + #define NR_GPIO_PORTS 4 + + /* SRAM size, in bytes */ + #define SRAM_SIZE 0x5000 #elif defined(MCU_STM32F103ZE) /* e.g., LeafLabs Maple Native */ - #define NR_GPIO_PORTS 7 - #define NR_GPIO_PINS 100 - #define NR_BKP_REGS 42 /* TODO test on Native */ - #define NR_TIMERS 8 - #define NR_USART 5 /* NB: 4 and 5 are UART only */ - #define NR_ADCS 3 - #define NR_FSMC 1 - #define NR_DAC_PINS 2 - - #define VCOM_ID_VENDOR 0x1EAF - #define VCOM_ID_PRODUCT 0x0004 - #define USB_DISC_BANK GPIOB_BASE - #define USB_DISC_PIN 8 - #define USB_CONFIG_MAX_POWER (100 >> 1) - #define RESET_DELAY (100) - - #define USER_ADDR_ROM 0x08005000 - #define USER_ADDR_RAM 0x20000C00 - #define STACK_TOP 0x20000800 - - #define ERROR_LED_PORT GPIOC_BASE - #define ERROR_LED_PIN 15 - #define ERROR_USART_NUM USART1 - #define ERROR_USART_BAUD 9600 - #define ERROR_TX_PORT GPIOA_BASE - #define ERROR_TX_PIN 10 - - #ifndef RAMSIZE - # define RAMSIZE (caddr_t)0x50000 - #endif - - #define BITBAND_SRAM_REF 0x20000000 - #define BITBAND_SRAM_BASE 0x22000000 - #define BITBAND_PERI_REF 0x40000000 - #define BITBAND_PERI_BASE 0x42000000 + #define NR_GPIO_PORTS 7 + + #define SRAM_SIZE 0x10000 #elif defined(MCU_STM32F103CB) /* e.g., LeafLabs Maple Mini */ - #define NR_GPIO_PORTS 3 - #define NR_GPIO_PINS 34 - #define NR_BKP_REGS 10 /* TODO test on Mini */ - #define NR_TIMERS 4 - #define NR_USART 3 - #define NR_ADCS 2 - #define NR_FSMC 0 - #define NR_DAC_PINS 0 - - #define VCOM_ID_VENDOR 0x1EAF - #define VCOM_ID_PRODUCT 0x0005 - #define USB_DISC_BANK GPIOB_BASE - #define USB_DISC_PIN 9 - #define USB_CONFIG_MAX_POWER (100 >> 1) - #define RESET_DELAY 100 - - #define USER_ADDR_ROM 0x08005000 - #define USER_ADDR_RAM 0x20000C00 - #define STACK_TOP 0x20000800 - - #define ERROR_LED_PORT GPIOB_BASE - #define ERROR_LED_PIN 12 - #define ERROR_USART_NUM USART2 - #define ERROR_USART_BAUD 9600 - #define ERROR_TX_PORT GPIOA_BASE - #define ERROR_TX_PIN 2 - - #ifndef RAMSIZE - # define RAMSIZE (caddr_t)0x50000 - #endif - - /* Bitbanded Memory sections */ - #define BITBAND_SRAM_REF 0x20000000 - #define BITBAND_SRAM_BASE 0x22000000 - #define BITBAND_PERI_REF 0x40000000 - #define BITBAND_PERI_BASE 0x42000000 + /* Note that this is not, strictly speaking, true. But only pins + 0 and 1 exist, and they're used for OSC on the Mini, so we'll + live with this for now. */ + #define NR_GPIO_PORTS 3 + + #define SRAM_SIZE 0x5000 #else @@ -190,8 +76,5 @@ #endif -/* Requires board configuration info */ -#include "util.h" - #endif diff --git a/libmaple/libmaple_types.h b/libmaple/libmaple_types.h index 8d216a8..a976a9e 100644 --- a/libmaple/libmaple_types.h +++ b/libmaple/libmaple_types.h @@ -45,8 +45,6 @@ typedef void (*voidFuncPtr)(void); #define __io volatile -#define ALWAYS_INLINE inline __attribute__((always_inline)) - #ifndef NULL #define NULL 0 #endif diff --git a/libmaple/timers.c b/libmaple/timers.c index 29aeeba..ff548c0 100644 --- a/libmaple/timers.c +++ b/libmaple/timers.c @@ -55,7 +55,7 @@ struct timer_dev timer_dev_table[] = { .rcc_dev_num = RCC_TIMER4, .nvic_dev_num = NVIC_TIMER4 }, -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY /* High density devices only (eg, Maple Native) */ [TIMER5] = { .base = (timer_port*)TIMER5_BASE, @@ -82,7 +82,7 @@ void timer_init(timer_dev_num timer_num, uint16 prescale) { if (timer_num == TIMER1) { is_advanced = 1; } -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY if (timer_num == TIMER8) { is_advanced = 1; } @@ -193,12 +193,8 @@ void timer_set_reload(timer_dev_num timer_num, uint16 max_reload) { * or similar to prevent interrupts and PWM output without 16 seperate function * calls to timer_set_mode */ void timer_disable_all(void) { - // TODO: refactor - - /* Note: this must be very robust because it gets called from, - e.g., ASSERT */ timer_port *timer; -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY timer_port *timers[6] = { (timer_port*)TIMER1_BASE, (timer_port*)TIMER2_BASE, (timer_port*)TIMER3_BASE, diff --git a/libmaple/timers.h b/libmaple/timers.h index 99bcab6..1f6afcd 100644 --- a/libmaple/timers.h +++ b/libmaple/timers.h @@ -206,7 +206,7 @@ typedef enum { TIMER2, /*< General purpose timer TIM2 */ TIMER3, /*< General purpose timer TIM3 */ TIMER4, /*< General purpose timer TIM4 */ -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY TIMER5, /*< General purpose timer TIM5; high density only */ /* FIXME maple native: put timers 6 and 7 back in and make the corresponding changes to timers.c */ @@ -412,8 +412,8 @@ void timer_generate_update(timer_dev_num timer_num); /** * Turn on PWM with duty_cycle. * - * @param ccr TIMERx_CHn_CCR, where x goes from 1 to NR_TIMERS, - * and n goes from 1 to 4. + * @param ccr TIMERx_CHn_CCR, where x ranges over timers, and n ranges + * from 1 to 4. * * @param duty_cycle: A number between 0 and * timer_get_compare_value(TIMERx, y), where x and y are as above. diff --git a/libmaple/usart.c b/libmaple/usart.c index 44a5c92..030d3cc 100644 --- a/libmaple/usart.c +++ b/libmaple/usart.c @@ -61,7 +61,7 @@ struct usart_dev usart_dev_table[] = { .rcc_dev_num = RCC_USART3, .nvic_dev_num = NVIC_USART3 }, -#if NR_USART >= 5 +#ifdef STM32_HIGH_DENSITY /* TODO test */ [UART4] = { .base = (usart_port*)UART4_BASE, @@ -107,7 +107,7 @@ void USART3_IRQHandler(void) { usart_irq(USART3); } -#if NR_USART >= 5 +#ifdef STM32_HIGH_DENSITY void UART4_IRQHandler(void) { usart_irq(UART4); } @@ -124,7 +124,11 @@ void UART5_IRQHandler(void) { * @param baud Baud rate to be set at */ void usart_init(uint8 usart_num, uint32 baud) { - ASSERT(usart_num <= NR_USART); +#ifdef STM32_HIGH_DENSITY + ASSERT(usart_num <= UART5); +#else + ASSERT(usart_num <= USART3); +#endif usart_port *port; ring_buffer *ring_buf; @@ -170,7 +174,7 @@ void usart_disable_all() { usart_disable(USART1); usart_disable(USART2); usart_disable(USART3); -#if NR_USART >= 5 +#ifdef STM32_HIGH_DENSITY usart_disable(UART4); usart_disable(UART5); #endif diff --git a/libmaple/usart.h b/libmaple/usart.h index 0ca3f55..90b3415 100644 --- a/libmaple/usart.h +++ b/libmaple/usart.h @@ -43,8 +43,10 @@ enum { USART1, USART2, USART3, +#ifdef STM32_HIGH_DENSITY UART4, UART5, +#endif }; /* peripheral register struct */ diff --git a/libmaple/usb/descriptors.c b/libmaple/usb/descriptors.c index 360e6dd..8dd9521 100644 --- a/libmaple/usb/descriptors.c +++ b/libmaple/usb/descriptors.c @@ -150,43 +150,50 @@ const USB_Descriptor_Config usbVcomDescriptor_Config = { // } }; -/* - String Identifiers: +/***************************************************************************** + ***************************************************************************** + *** + *** FIXME FIXME FIXME NOT THE RIGHT THING! MOVE ALL THIS INTO TO WIRISH! + *** + ***************************************************************************** + *****************************************************************************/ - we may choose to specify any or none of the following string - identifiers: +const uint8 usbVcomDescriptor_LangID[USB_DESCRIPTOR_STRING_LEN(1)] = { + USB_DESCRIPTOR_STRING_LEN(1), + USB_DESCRIPTOR_TYPE_STRING, + 0x09, + 0x04 +}; - iManufacturer: LeafLabs - iProduct: Maple R3 - iSerialNumber: NONE - iConfiguration: NONE - iInterface(CCI): NONE - iInterface(DCI): NONE +const uint8 usbVcomDescriptor_iManufacturer[USB_DESCRIPTOR_STRING_LEN(8)] = { + USB_DESCRIPTOR_STRING_LEN(8), + USB_DESCRIPTOR_TYPE_STRING, + 'L', 0, 'e', 0, 'a', 0, 'f', 0, + 'L', 0, 'a', 0, 'b', 0, 's', 0 +}; - additionally we must provide the unicode language identifier, - which is 0x0409 for US English -*/ +/* + String Identifiers: -const uint8 usbVcomDescriptor_LangID[USB_DESCRIPTOR_STRING_LEN(1)] = -{ - USB_DESCRIPTOR_STRING_LEN(1), - USB_DESCRIPTOR_TYPE_STRING, - 0x09, - 0x04 -}; + we may choose to specify any or none of the following string + identifiers: -const uint8 usbVcomDescriptor_iManufacturer[USB_DESCRIPTOR_STRING_LEN(8)] = -{ - USB_DESCRIPTOR_STRING_LEN(8), - USB_DESCRIPTOR_TYPE_STRING, - 'L', 0, 'e', 0, 'a', 0, 'f', 0, - 'L', 0, 'a', 0, 'b', 0, 's', 0 -}; + iManufacturer: LeafLabs + iProduct: Maple R3 + iSerialNumber: NONE + iConfiguration: NONE + iInterface(CCI): NONE + iInterface(DCI): NONE -const uint8 usbVcomDescriptor_iProduct[USB_DESCRIPTOR_STRING_LEN(8)] = -{ - USB_DESCRIPTOR_STRING_LEN(8), - USB_DESCRIPTOR_TYPE_STRING, - 'M', 0, 'a', 0, 'p', 0, 'l', 0, - 'e', 0, ' ', 0, 'R', 0, '3', 0 + additionally we must provide the unicode language identifier, + which is 0x0409 for US English +*/ +const uint8 usbVcomDescriptor_iProduct[USB_DESCRIPTOR_STRING_LEN(8)] = { + USB_DESCRIPTOR_STRING_LEN(8), + USB_DESCRIPTOR_TYPE_STRING, + 'M', 0, 'a', 0, 'p', 0, 'l', 0, + 'e', 0, ' ', 0, ' ', 0, ' ', 0 }; + +/***************************************************************************** + *****************************************************************************/ diff --git a/libmaple/usb/usb_config.h b/libmaple/usb/usb_config.h index e5f3979..394c580 100644 --- a/libmaple/usb/usb_config.h +++ b/libmaple/usb/usb_config.h @@ -5,6 +5,67 @@ #include "usb_lib.h" +/****************************************************************************** + ****************************************************************************** + *** + *** HACK ALERT + *** + *** FIXME FIXME FIXME FIXME + *** + *** A bunch of board-specific #defines that are only used by the + *** USB routines got put into libmaple.h for what appear to be + *** historical reasons. I'm [mbolivar] putting them in here for + *** now, so that we can treat the usb/ directory as a black box, + *** freeing the rest of libmaple/ to be implemented as a + *** general-purpose STM32 library. All of this REALLY needs to get + *** moved into wirish when we get a chance to redo the USB stack. + *** + ****************************************************************************** + *****************************************************************************/ + +#define VCOM_ID_VENDOR 0x1EAF +#define RESET_DELAY (100) +#define USB_CONFIG_MAX_POWER (100 >> 1) + +#if defined(BOARD_maple) + + /* USB Identifier numbers */ + #define VCOM_ID_PRODUCT 0x0004 + #define USB_DISC_BANK GPIOC_BASE + #define USB_DISC_PIN 12 + +#elif defined(BOARD_maple_mini) + + #define VCOM_ID_PRODUCT 0x0005 + #define USB_DISC_BANK GPIOB_BASE + #define USB_DISC_PIN 9 + +#elif defined(BOARD_maple_native) + + #define VCOM_ID_PRODUCT 0x0006 + #define USB_DISC_BANK GPIOB_BASE + #define USB_DISC_PIN 8 + +#else + +#error ("Sorry! the USB stack relies on LeafLabs board-specific " \ + "configuration right now. If you want, you can pretend you're one " \ + "of our boards; i.e., #define BOARD_maple, BOARD_maple_mini, or " \ + "BOARD_maple_native according to what matches your MCU best. " \ + "You should also take a look at libmaple/usb/descriptors.c; we make " \ + "some assumptions there that you probably won't like.") + +#endif + +/****************************************************************************** + ****************************************************************************** + *** + *** END HACK + *** + ****************************************************************************** + *****************************************************************************/ + + /* choose addresses to give endpoints the max 64 byte buffers */ #define USB_BTABLE_ADDRESS 0x00 #define VCOM_CTRL_EPNUM 0x00 @@ -33,14 +94,15 @@ #define NUM_ENDPTS 0x04 /* handle all usb interrupts */ -#define ISR_MSK ( CNTR_CTRM | \ - CNTR_WKUPM | \ - CNTR_SUSPM | \ - CNTR_ERRM | \ - CNTR_SOFM | \ - CNTR_ESOFM | \ - CNTR_RESETM ) +#define ISR_MSK (CNTR_CTRM | \ + CNTR_WKUPM | \ + CNTR_SUSPM | \ + CNTR_ERRM | \ + CNTR_SOFM | \ + CNTR_ESOFM | \ + CNTR_RESETM) #define F_SUSPEND_ENABLED 1 + #endif diff --git a/libmaple/util.c b/libmaple/util.c index 11f9b34..481cd60 100644 --- a/libmaple/util.c +++ b/libmaple/util.c @@ -34,6 +34,21 @@ #include "adc.h" #include "timers.h" +/* Failed asserts send out a message on this USART. */ +#ifndef ERROR_USART_NUM +#define ERROR_USART_NUM USART2 +#define ERROR_USART_BAUD 9600 +#define ERROR_TX_PORT GPIOA_BASE +#define ERROR_TX_PIN 2 +#endif + +/* If you define ERROR_LED_PORT and ERROR_LED_PIN, then a failed + assert will also throb an LED connected to that port an pin. + FIXME this should work together with wirish somehow. */ +#if defined(ERROR_LED_PORT) && defined(ERROR_LED_PIN) +#define HAVE_ERROR_LED +#endif + /* Error assert + fade */ void _fail(const char* file, int line, const char* exp) { int32 slope = 1; @@ -67,8 +82,10 @@ void _fail(const char* file, int line, const char* exp) { usart_putc(ERROR_USART_NUM, '\n'); usart_putc(ERROR_USART_NUM, '\r'); +#ifdef HAVE_ERROR_LED /* Turn on the error LED */ gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_MODE_OUTPUT_PP); +#endif /* Turn the USB interrupt back on so the bootloader keeps on functioning */ nvic_irq_enable(NVIC_INT_USBHP); @@ -79,6 +96,7 @@ void _fail(const char* file, int line, const char* exp) { } void throb(void) { +#ifdef HAVE_ERROR_LED int32 slope = 1; uint32 CC = 0x0000; uint32 TOP_CNT = 0x0200; @@ -105,5 +123,10 @@ void throb(void) { } i++; } +#else + /* No error LED is connected; do nothing. */ + while (1) + ; +#endif } diff --git a/libmaple/util.h b/libmaple/util.h index 63427cc..28ce970 100644 --- a/libmaple/util.h +++ b/libmaple/util.h @@ -32,7 +32,18 @@ #ifndef _UTIL_H_ #define _UTIL_H_ -#include "libmaple.h" +#ifdef __cplusplus +extern "C"{ +#endif + +/* Debug configuration */ +#define DEBUG_NONE 0 +#define DEBUG_FAULT 1 +#define DEBUG_ALL 2 + +#ifndef DEBUG_LEVEL +#define DEBUG_LEVEL DEBUG_ALL +#endif #define BIT(shift) (1UL << (shift)) #define BIT_MASK_SHIFT(mask, shift) ((mask) << (shift)) @@ -41,9 +52,14 @@ #define GET_BITS(x, m, n) ((((uint32)x) << (31 - (n))) >> ((31 - (n)) + (m))) /* Bit-banding macros */ +/* Bitbanded Memory sections */ +#define BITBAND_SRAM_REF 0x20000000 +#define BITBAND_SRAM_BASE 0x22000000 +#define BITBAND_PERI_REF 0x40000000 +#define BITBAND_PERI_BASE 0x42000000 /* Convert SRAM address */ #define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE+(a-BITBAND_SRAM_REF)*32+(b*4))) -/* Convert PERI address */ +/* Convert peripheral address */ #define BITBAND_PERI(a, b) ((BITBAND_PERI_BASE + \ ((uint32)a - BITBAND_PERI_REF) * 32 + (b * 4))) @@ -63,18 +79,9 @@ #define __write(reg, value) (*(volatile uint32*)(reg) = (value)) #define IS_POWER_OF_TWO(v) (v && !(v & (v - 1))) - -#ifdef __cplusplus -extern "C"{ -#endif - void _fail(const char*, int, const char*); void throb(void); -#ifdef __cplusplus -} // extern "C" -#endif - /* Asserts for sanity checks, redefine DEBUG_LEVEL in libmaple.h to * compile out these checks */ @@ -100,5 +107,9 @@ void throb(void); #define ASSERT_FAULT(exp) (void)((0)) #endif +#ifdef __cplusplus +} // extern "C" +#endif + #endif diff --git a/wirish/HardwareTimer.cpp b/wirish/HardwareTimer.cpp index 354663e..0f8bec6 100644 --- a/wirish/HardwareTimer.cpp +++ b/wirish/HardwareTimer.cpp @@ -199,7 +199,7 @@ HardwareTimer Timer1(TIMER1); HardwareTimer Timer2(TIMER2); HardwareTimer Timer3(TIMER3); HardwareTimer Timer4(TIMER4); -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY HardwareTimer Timer5(TIMER5); // High-density devices only HardwareTimer Timer8(TIMER8); // High-density devices only #endif @@ -214,7 +214,7 @@ HardwareTimer* getTimer(timer_dev_num timerNum) { return &Timer3; case TIMER4: return &Timer4; -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY case TIMER5: return &Timer5; case TIMER8: diff --git a/wirish/HardwareTimer.h b/wirish/HardwareTimer.h index 4034b1f..4030adc 100644 --- a/wirish/HardwareTimer.h +++ b/wirish/HardwareTimer.h @@ -382,7 +382,7 @@ extern HardwareTimer Timer2; extern HardwareTimer Timer3; /** Pre-instantiated timer for use by user code. */ extern HardwareTimer Timer4; -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY /** Pre-instantiated timer for use by user code, on devices with more than four timers (this does not include the Maple). */ extern HardwareTimer Timer5; diff --git a/wirish/boards.h b/wirish/boards.h index ac3a74d..989eea1 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -70,8 +70,12 @@ typedef struct PinMapping { #define CYCLES_PER_MICROSECOND 72 #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - #define BOARD_BUTTON_PIN 38 - #define BOARD_LED_PIN 13 + #define BOARD_BUTTON_PIN 38 + #define BOARD_LED_PIN 13 + + /* Total number of GPIO pins that are broken out to headers and + intended for general use. */ + #define NR_GPIO_PINS 39 static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D0/PA3 */ @@ -173,6 +177,8 @@ typedef struct PinMapping { #define BOARD_LED_PIN D21 #define BOARD_BUTTON_PIN D18 + #define NR_GPIO_PINS 100 + static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { /* Top header */ @@ -390,11 +396,13 @@ typedef struct PinMapping { #elif defined(BOARD_maple_mini) - #define CYCLES_PER_MICROSECOND 72 + #define CYCLES_PER_MICROSECOND 72 #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - #define BOARD_BUTTON_PIN 32 - #define BOARD_LED_PIN 33 + #define BOARD_BUTTON_PIN 32 + #define BOARD_LED_PIN 33 + + #define NR_GPIO_PINS 34 static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D0/PB11 */ diff --git a/wirish/ext_interrupts.h b/wirish/ext_interrupts.h index 304e267..4e22c71 100644 --- a/wirish/ext_interrupts.h +++ b/wirish/ext_interrupts.h @@ -86,7 +86,7 @@ void detachInterrupt(uint8 pin); * * @see noInterrupts() */ -static ALWAYS_INLINE void interrupts() { +static inline void interrupts() { nvic_globalirq_enable(); } @@ -100,7 +100,7 @@ static ALWAYS_INLINE void interrupts() { * * @see interrupts() */ -static ALWAYS_INLINE void noInterrupts() { +static inline void noInterrupts() { nvic_globalirq_disable(); } diff --git a/wirish/wirish.c b/wirish/wirish.c index c5dec22..4c84d26 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -47,7 +47,7 @@ void init(void) { flash_enable_prefetch(); flash_set_latency(FLASH_WAIT_STATE_2); -#if NR_FSMC > 0 +#ifdef STM32_HIGH_DENSITY fsmc_native_sram_init(); #endif @@ -70,7 +70,7 @@ void init(void) { timer_init(TIMER2, 1); timer_init(TIMER3, 1); timer_init(TIMER4, 1); -#if NR_TIMERS >= 8 +#ifdef STM32_HIGH_DENSITY timer_init(TIMER5, 1); timer_init(TIMER8, 1); #endif -- cgit v1.2.3 From 52d5cc53307cce58c86aa74ccd9010bbad59ff63 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 4 Mar 2011 19:16:07 -0500 Subject: Cosmetic changes to wirish/main.cxx --- wirish/main.cxx | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) (limited to 'wirish') diff --git a/wirish/main.cxx b/wirish/main.cxx index f0158f8..dd5e296 100644 --- a/wirish/main.cxx +++ b/wirish/main.cxx @@ -1,4 +1,4 @@ -/* ***************************************************************************** +/****************************************************************************** * The MIT License * * Copyright (c) 2010 LeafLabs LLC. @@ -20,16 +20,15 @@ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * THE SOFTWARE. - * ****************************************************************************/ + *****************************************************************************/ // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. +// Otherwise, statically allocated objects that need libmaple may fail. __attribute__(( constructor )) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { -- cgit v1.2.3 From 02e76ec27b5737bce836a5460427b538076f01ef Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 4 Mar 2011 20:25:26 -0500 Subject: Brought examples/ up to date; PIN_MAP bugfix for D24. --- examples/blinky.cpp | 6 +- examples/debug-dtrrts.cpp | 23 ++--- examples/qa-slave-shield.cpp | 45 ++++----- examples/spi_master.cpp | 7 +- examples/test-bkp.cpp | 2 +- examples/test-dac.cpp | 4 - examples/test-fsmc.cpp | 22 ++--- examples/test-serial-flush.cpp | 18 +--- examples/test-serialusb.cpp | 74 +++++++------- examples/test-systick.cpp | 50 +++++----- examples/test-timers.cpp | 68 ++++++------- examples/vga-leaf.cpp | 162 +++++++++++++++++++------------ examples/vga-scope.cpp | 212 ++++++++++++++++++++++++++--------------- wirish/boards.h | 2 +- 14 files changed, 381 insertions(+), 314 deletions(-) (limited to 'wirish') diff --git a/examples/blinky.cpp b/examples/blinky.cpp index 5611987..209a6e6 100644 --- a/examples/blinky.cpp +++ b/examples/blinky.cpp @@ -1,4 +1,4 @@ -// Blinks the LED, pin 13 +// Blinks the built-in LED #include "wirish.h" @@ -20,8 +20,8 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } diff --git a/examples/debug-dtrrts.cpp b/examples/debug-dtrrts.cpp index f9f8b96..61c061a 100644 --- a/examples/debug-dtrrts.cpp +++ b/examples/debug-dtrrts.cpp @@ -1,14 +1,12 @@ -// Sample main.cpp file. Blinks an LED, sends a message out USART2 -// and turns on PWM on pin 2 +// Test sketch for figuring out DTR/RTS behavior on different platforms. #include "wirish.h" #include "usb.h" -#define LED_PIN 13 -#define PWM_PIN 2 +#define LED_PIN BOARD_LED_PIN +#define PWM_PIN 2 -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); @@ -18,12 +16,10 @@ void setup() } -int toggle = 0; - void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); + Serial2.print("DTR: "); Serial2.print(usbGetDTR(), DEC); Serial2.print("\tRTS: "); @@ -31,13 +27,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/qa-slave-shield.cpp b/examples/qa-slave-shield.cpp index b395cca..178b780 100644 --- a/examples/qa-slave-shield.cpp +++ b/examples/qa-slave-shield.cpp @@ -1,50 +1,51 @@ -// slave mode for QA shield +// Slave mode for QA shield #include "wirish.h" -#define LED_PIN 13 -#define NUM_GPIO 38 // not the number of the max... +// FIXME generalize for Maple Native, Maple Mini (NUM_GPIO, Mini USB +// breakout pins, etc.) -int i; +#define LED_PIN BOARD_LED_PIN +#define NUM_GPIO 38 // Ignore JTAG pins. -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); - digitalWrite(LED_PIN, 1); + digitalWrite(LED_PIN, HIGH); - for(i=0; i +#include // for snprintf() #include "wirish.h" #include "bkp.h" diff --git a/examples/test-dac.cpp b/examples/test-dac.cpp index 62f40eb..af98030 100644 --- a/examples/test-dac.cpp +++ b/examples/test-dac.cpp @@ -1,8 +1,4 @@ - #include "wirish.h" -#include "fsmc.h" -#include "rcc.h" -#include "gpio.h" #include "dac.h" uint16 count = 0; diff --git a/examples/test-fsmc.cpp b/examples/test-fsmc.cpp index f4fd068..4211e4d 100644 --- a/examples/test-fsmc.cpp +++ b/examples/test-fsmc.cpp @@ -1,14 +1,12 @@ - #include "wirish.h" #include "fsmc.h" -#define LED_PIN 23 // hack for maple native -#define DISC_PIN 14 // hack for USB on native +#define LED_PIN BOARD_LED_PIN // System control block registers #define SCB_BASE (SCB_Reg*)(0xE000ED00) -// This stuff should ultimately get moved to util.h or scb.h or w/e. +// This stuff should ultimately get moved to util.h or scb.h or w/e. // Also in interactive test program and the HardFault IRQ handler. typedef struct { volatile uint32 CPUID; @@ -23,15 +21,14 @@ typedef struct { volatile uint32 SHCRS; volatile uint32 CFSR; volatile uint32 HFSR; - uint32 pad1; + uint32 pad1; volatile uint32 MMAR; volatile uint32 BFAR; } SCB_Reg; -SCB_Reg *scb; +SCB_Reg *scb; uint16 *ptr; -int toggle = 0; int count = 0; void setup() { @@ -39,8 +36,6 @@ void setup() { scb = (SCB_Reg*)SCB_BASE; pinMode(LED_PIN, OUTPUT); - pinMode(DISC_PIN, OUTPUT); - digitalWrite(DISC_PIN,1); digitalWrite(LED_PIN,1); Serial1.begin(9600); @@ -82,15 +77,14 @@ void setup() { Serial1.print("BFAR: "); id = scb->BFAR; Serial1.println(id,BIN); - + Serial1.println("Now testing all memory addresses... (will hardfault at the end)"); delay(3000); } void loop() { - digitalWrite(LED_PIN, toggle); - toggle ^= 1; - delay(1); + toggleLED(); + delay(1); for(int i = 0; i<100; i++) { // modify this to speed things up count++; @@ -102,7 +96,7 @@ void loop() { while(1) { } } } - + Serial1.print((uint32)(ptr),HEX); Serial1.print(": "); Serial1.println(*ptr,BIN); diff --git a/examples/test-serial-flush.cpp b/examples/test-serial-flush.cpp index d7fbf7a..1cd82b6 100644 --- a/examples/test-serial-flush.cpp +++ b/examples/test-serial-flush.cpp @@ -2,22 +2,13 @@ #include "wirish.h" -void setup() -{ +void setup() { /* Send a message out USART2 */ Serial2.begin(9600); Serial2.println("Hello world!"); } -int toggle = 0; - void loop() { - - Serial2.println("This is the first line."); - Serial2.end(); - Serial2.println("This is the second line."); - - Serial2.begin(9600); Serial2.println("Waiting for multiple input..."); while(Serial2.available() < 5) { } Serial2.println(Serial2.read()); @@ -29,13 +20,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-serialusb.cpp b/examples/test-serialusb.cpp index 9d0a862..678c2b9 100644 --- a/examples/test-serialusb.cpp +++ b/examples/test-serialusb.cpp @@ -1,11 +1,10 @@ -// Sample main.cpp file. Blinks an LED, sends a message out USART2 -// and turns on PWM on pin 2 +// Tests SerialUSB functionality. #include "wirish.h" #include "usb.h" -#define LED_PIN 13 -#define BUT_PIN 38 +#define LED_PIN BOARD_LED_PIN +#define BUT_PIN BOARD_BUTTON_PIN uint32 state = 0; #define QUICKPRINT 0 @@ -14,33 +13,29 @@ uint32 state = 0; #define SIMPLE 3 #define ONOFF 4 - -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); /* Set up the Button */ - pinMode(BUT_PIN, INPUT_PULLUP); + pinMode(BUT_PIN, INPUT); Serial2.begin(9600); - Serial2.println("Hello world! This is the debug channel."); -} + Serial2.println("This is the debug channel. Press BUT."); -int toggle = 0; + waitForButtonPress(0); +} uint8 c1 = '-'; void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(1000); - if(digitalRead(BUT_PIN)) { - while(digitalRead(BUT_PIN)) {}; + if(isButtonPressed()) { state++; } - + switch(state) { case QUICKPRINT: for(int i = 0; i<30; i++) { @@ -48,34 +43,34 @@ void loop() { SerialUSB.print('.'); SerialUSB.print('|'); } - Serial2.println(SerialUSB.pending(),DEC); + Serial2.println(SerialUSB.pending(), DEC); SerialUSB.println(); break; case BIGSTUFF: - SerialUSB.println("01234567890123456789012345678901234567890123456789012345678901234567890123456789012345678901234567890"); - SerialUSB.println((uint32)123456789,DEC); + SerialUSB.println("0123456789012345678901234567890123456789" + "0123456789012345678901234567890123456789" + "012345678901234567890"); + SerialUSB.println((int64)123456789, DEC); SerialUSB.println(3.1415926535); - Serial2.println(SerialUSB.pending(),DEC); + Serial2.println(SerialUSB.pending(), DEC); break; case NUMBERS: SerialUSB.println("Numbers! -----------------------------"); Serial2.println("Numbers! -----------------------------"); SerialUSB.println('1'); Serial2.println('1'); - SerialUSB.println(1,DEC); - Serial2.println(1,DEC); - SerialUSB.println(-1,DEC); - Serial2.println(-1,DEC); + SerialUSB.println(1, DEC); + Serial2.println(1, DEC); + SerialUSB.println(-1, DEC); + Serial2.println(-1, DEC); SerialUSB.println(3.14159265); Serial2.println(3.14159265); - SerialUSB.println(3.14159265,9); - Serial2.println(3.14159265,9); - SerialUSB.println(123456789,DEC); - Serial2.println(123456789,DEC); - SerialUSB.println(-123456789,DEC); - Serial2.println(-123456789,DEC); - SerialUSB.println(65535,HEX); - Serial2.println(65535,HEX); + SerialUSB.println(123456789, DEC); + Serial2.println(123456789, DEC); + SerialUSB.println(-123456789, DEC); + Serial2.println(-123456789, DEC); + SerialUSB.println(65535, HEX); + Serial2.println(65535, HEX); break; case SIMPLE: Serial2.println("Trying write('a')"); @@ -92,8 +87,8 @@ void loop() { SerialUSB.print("hij\n\r"); SerialUSB.write(' '); SerialUSB.println(); - Serial2.println("Trying println(123456789,DEC)"); - SerialUSB.println(123456789); + Serial2.println("Trying println(123456789, DEC)"); + SerialUSB.println(123456789, DEC); Serial2.println("Trying println(3.141592)"); SerialUSB.println(3.141592); Serial2.println("Trying println(\"DONE\")"); @@ -103,12 +98,12 @@ void loop() { Serial2.println("Shutting down..."); SerialUSB.println("Shutting down..."); SerialUSB.end(); - Serial2.println("Waiting 4seconds..."); + Serial2.println("Waiting 4 seconds..."); delay(4000); Serial2.println("Starting up..."); SerialUSB.begin(); SerialUSB.println("Hello World!"); - Serial2.println("Waiting 4seconds..."); + Serial2.println("Waiting 4 seconds..."); delay(4000); state++; break; @@ -118,13 +113,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-systick.cpp b/examples/test-systick.cpp index 247892d..c7b5529 100644 --- a/examples/test-systick.cpp +++ b/examples/test-systick.cpp @@ -3,54 +3,48 @@ #include "wirish.h" #include "systick.h" -#define LED_PIN 13 -#define PWM_PIN 2 -#define BUT 38 +#define LED_PIN BOARD_LED_PIN +#define PWM_PIN 2 +#define BUT BOARD_BUTTON_PIN -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); - - /* Turn on PWM on pin PWM_PIN */ - pinMode(PWM_PIN, PWM); - pwmWrite(PWM_PIN, 0x8000); - - pinMode(BUT, INPUT_PULLDOWN); + pinMode(BUT, INPUT); } -int toggle = 0; +bool disable = true; long time = 0; void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + volatile int i = 0; + toggleLED(); // An artificial delay - int16 i = 1; - float j = 1; - for(i=0; i<6553; i++) { - j = sqrt(j) + 1; - } - - if(digitalRead(BUT)) { - systick_disable(); - } else { - systick_resume(); + for(i = 0; i < 150000; i++) + ; + + if(isButtonPressed()) { + if (disable) { + systick_disable(); + SerialUSB.println("Disabling SysTick"); + } else { + SerialUSB.println("Re-enabling SysTick"); + systick_resume(); + } + disable = !disable; } - //SerialUSB.println(micros()); // there is a bug with this SerialUSB.println(millis()); } // Force init to be called *first*, i.e. before static object allocation. // Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-timers.cpp b/examples/test-timers.cpp index ccba251..f3cfdcc 100644 --- a/examples/test-timers.cpp +++ b/examples/test-timers.cpp @@ -2,7 +2,7 @@ #include "wirish.h" -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN void handler1(void); void handler2(void); @@ -12,7 +12,6 @@ void handler4(void); void handler3b(void); void handler4b(void); -int toggle = 0; int t; int count1 = 0; @@ -36,25 +35,24 @@ void setup() pinMode(LED_PIN, OUTPUT); // Setup the button as input - pinMode(38, INPUT_PULLUP); + pinMode(BOARD_BUTTON_PIN, INPUT); - /* Send a message out USART2 */ - //SerialUSB.begin(9600); - SerialUSB.println("Begining timer test..."); + // Wait for user to attach... + waitForButtonPress(0); + + // Send a message out SerialUSB + SerialUSB.println("Beginning timer test..."); for(int t=0; t<4; t++) { Timers[t].setChannel1Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel2Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel3Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel4Mode(TIMER_OUTPUTCOMPARE); } - - // Wait for user to attach... - delay(2000); } void loop() { SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setCount/getCount"); + SerialUSB.println("Testing setCount/getCount"); SerialUSB.print("Timer1.getCount() = "); SerialUSB.println(Timer1.getCount()); SerialUSB.println("Timer1.setCount(1234)"); Timer1.setCount(1234); @@ -63,7 +61,7 @@ void loop() { // down Timer4 is in the "pause" state and the timer doesn't increment, so // the final counts should reflect the ratio of time that BUT was held down SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing Pause/Resume; button roughly controls Timer4"); + SerialUSB.println("Testing Pause/Resume; button roughly controls Timer4"); count3 = 0; count4 = 0; Timer3.setChannel1Mode(TIMER_OUTPUTCOMPARE); @@ -80,9 +78,9 @@ void loop() { Timer4.attachCompare1Interrupt(handler4b); Timer3.resume(); Timer4.resume(); - SerialUSB.println("~4 seconds..."); + SerialUSB.println("~4 seconds..."); for(int i = 0; i<4000; i++) { - if(digitalRead(38)) { + if(isButtonPressed()) { Timer4.pause(); } else { Timer4.resume(); @@ -96,14 +94,14 @@ void loop() { // These test the setPeriod auto-configure functionality SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setPeriod"); + SerialUSB.println("Testing setPeriod"); Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); - Timer4.setPeriod(10); + Timer4.setPeriod(10); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 10ms, wait 2 seconds..."); + SerialUSB.println("Period 10ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -114,10 +112,10 @@ void loop() { Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); Timer4.pause(); - Timer4.setPeriod(30000); + Timer4.setPeriod(30000); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -127,12 +125,12 @@ void loop() { SerialUSB.println("(should be around 2sec/30000ms ~ 67)"); Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setPeriod(300000); + Timer4.setPeriod(300000); Timer4.setCompare1(1); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 300000ms, wait 2 seconds..."); + SerialUSB.println("Period 300000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -146,9 +144,9 @@ void loop() { Timer4.setOverflow(65454); Timer4.pause(); Timer4.setCount(0); - Timer4.setCompare1(1); + Timer4.setCompare1(1); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -159,11 +157,11 @@ void loop() { Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); - Timer4.setPeriod(30000); + Timer4.setPeriod(30000); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -177,7 +175,7 @@ void loop() { // that over time the actual timing rates get blown away by other system // interrupts. for(t=0; t<4; t++) { - toggle ^= 1; digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); SerialUSB.println("-----------------------------------------------------"); SerialUSB.print("Testing Timer "); SerialUSB.println(t+1); @@ -214,33 +212,39 @@ void handler1(void) { val1 += rate1; Timers[t].setCompare1(val1); count1++; -} +} + void handler2(void) { val2 += rate2; Timers[t].setCompare2(val2); count2++; -} +} + void handler3(void) { val3 += rate3; Timers[t].setCompare3(val3); count3++; -} +} + void handler4(void) { val4 += rate4; Timers[t].setCompare4(val4); count4++; -} +} void handler3b(void) { count3++; -} +} + void handler4b(void) { count4++; -} +} +__attribute__((constructor)) void premain() { + init(); +} int main(void) { - init(); setup(); while (1) { diff --git a/examples/vga-leaf.cpp b/examples/vga-leaf.cpp index d1c6d7d..9d9fce2 100644 --- a/examples/vga-leaf.cpp +++ b/examples/vga-leaf.cpp @@ -1,21 +1,21 @@ /* - Crude VGA Output + VGA Output - Outputs a red and white leaf to VGA. This implementation is crude and noisy, - but a fun demo. It should run most VGA monitors at 640x480, though it does - not follow the timing spec very carefully. Real twisted or shielded wires, - proper grounding, and not doing this on a breadboard are recommended (but - it seems to work ok without). + Outputs a red and white leaf to VGA. It should run most VGA monitors + at 640x480, though it does not follow the timing spec very + carefully. Real twisted or shielded wires, proper grounding, and not + doing this on a breadboard are recommended (but it seems to work ok + without). - SerialUSB is disabled to get rid of most interrupts (which mess with timing); - the SysTick is probably the source of the remaining flickers. This means that - you have to use perpetual bootloader or the reset button to flash new - programs. + SerialUSB and SysTick are disabled to get rid of the most frequently + occurring interrupts (which mess with timing). This means that you + have to use perpetual bootloader mode or the reset button to flash + new programs. How to wire this to a VGA port: - D5 via ~200ohms to VGA Red (1) - D6 via ~200ohms to VGA Green (2) - D7 via ~200ohms to VGA Blue (3) + D6 via ~200ohms to VGA Red (1) + D7 via ~200ohms to VGA Green (2) + D8 via ~200ohms to VGA Blue (3) D11 to VGA VSync (14) (swapped?) D12 to VGA HSync (13) (swapped?) GND to VGA Ground (5) @@ -24,48 +24,71 @@ See also: - http://pinouts.ru/Video/VGA15_pinout.shtml - http://www.epanorama.net/documents/pc/vga_timing.html - + Created 20 July 2010 By Bryan Newbold for LeafLabs This code is released with no strings attached. - + + Modified 4 March 2011 + By Marti Bolivar + Disabled SysTick, kept up-to-date with libmaple. */ +// FIXME: generalize for Native and Mini + #include "wirish.h" -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN -// Pinouts -#define VGA_R 5 // STM32: B6 -#define VGA_G 6 // STM32: A8 -#define VGA_B 7 // STM32: A9 +// Pinouts -- you also must change the GPIO macros below if you change +// these +#define VGA_R 6 // STM32: A8 +#define VGA_G 7 // STM32: A9 +#define VGA_B 8 // STM32: A10 #define VGA_V 11 // STM32: A6 #define VGA_H 12 // STM32: A7 -// These low level macros make GPIO writes much faster -#define VGA_R_HIGH (GPIOB_BASE)->BSRR = BIT(6) -#define VGA_R_LOW (GPIOB_BASE)->BRR = BIT(6) -#define VGA_G_HIGH (GPIOA_BASE)->BSRR = BIT(8) -#define VGA_G_LOW (GPIOA_BASE)->BRR = BIT(8) -#define VGA_B_HIGH (GPIOA_BASE)->BSRR = BIT(9) -#define VGA_B_LOW (GPIOA_BASE)->BRR = BIT(9) -#define VGA_V_HIGH (GPIOA_BASE)->BSRR = BIT(6) -#define VGA_V_LOW (GPIOA_BASE)->BRR = BIT(6) -#define VGA_H_HIGH (GPIOA_BASE)->BSRR = BIT(7) -#define VGA_H_LOW (GPIOA_BASE)->BRR = BIT(7) +// These low level (and STM32 specific) macros make GPIO writes much +// faster +#define ABSRR ((volatile uint32*)0x40010810) +#define ABRR ((volatile uint32*)0x40010814) + +#define RBIT 8 // (see pinouts) +#define GBIT 9 +#define BBIT 10 + +#define VGA_R_HIGH *ABSRR = BIT(RBIT) +#define VGA_R_LOW *ABRR = BIT(RBIT) +#define VGA_G_HIGH *ABSRR = BIT(GBIT) +#define VGA_G_LOW *ABRR = BIT(GBIT) +#define VGA_B_HIGH *ABSRR = BIT(BBIT) +#define VGA_B_LOW *ABRR = BIT(BBIT) + +#define ON_COLOR BIT(RBIT) +#define OFF_COLOR (BIT(RBIT) | BIT(GBIT) | BIT(BBIT)) + +// set has priority, so clear every bit and set some given bits: +#define VGA_COLOR(c) (*ABSRR = c | \ + BIT(RBIT+16) | BIT(GBIT+16) | BIT(BBIT+16)) + +#define VGA_V_HIGH *ABSRR = BIT(6) +#define VGA_V_LOW *ABRR = BIT(6) +#define VGA_H_HIGH *ABSRR = BIT(7) +#define VGA_H_LOW *ABRR = BIT(7) void isr_porch(void); void isr_start(void); void isr_stop(void); void isr_update(void); -uint8 toggle; uint16 x = 0; // X coordinate uint16 y = 0; // Y coordinate -uint8 v_active = 1; // Are we in the image? +uint16 logo_y = 0; // Y coordinate, mapped into valid logo index (for speed) +bool v_active = true; // Are we in the image? -// 1-bit! -uint8 logo[18][16] = { +const uint8 x_max = 16; +const uint8 y_max = 18; +uint32 logo[y_max][x_max] = { {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,}, {0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,}, {0,0,0,0,0,1,0,0,0,1,0,0,0,0,0,0,}, @@ -99,9 +122,20 @@ void setup() { digitalWrite(VGA_H, HIGH); digitalWrite(VGA_V, HIGH); + // Fill the logo array with color patterns corresponding to its + // truth value. Note that we could get more tricky here, since + // there are 3 bits of color. + for (int y = 0; y < y_max; y++) { + for (int x = 0; x < x_max; x++) { + logo[y][x] = logo[y][x] ? ON_COLOR : OFF_COLOR; + } + } + // This gets rid of the majority of the interrupt artifacts; + // there's still a glitch for low values of y, but let's not worry + // about that. (Probably due to the hackish way vsync is done). SerialUSB.end(); - SystemTick.end(); + systick_disable(); // Configure Timer4.pause(); // while we configure @@ -120,14 +154,13 @@ void setup() { Timer4.attachCompare3Interrupt(isr_stop); Timer4.setCompare4(1); // Could be zero I guess Timer4.attachCompare4Interrupt(isr_update); - + Timer4.setCount(0); // Ready... Timer4.resume(); // Go! } void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); // Everything happens in the interrupts! @@ -139,51 +172,59 @@ void loop() { void isr_porch(void) { VGA_H_HIGH; y++; + logo_y = map(y, 0, 478, 0, y_max); // Back to the top - if(y>=523) { - y=1; - v_active = 1; + if(y >= 523) { + y = 1; + logo_y = 0; + v_active = true; return; } // Other vsync stuff below the image - if(y>=492) { + if(y >= 492) { VGA_V_HIGH; return; } - if(y>=490) { + if(y >= 490) { VGA_V_LOW; return; } - if(y>=479) { - v_active = 0; + if(y >= 479) { + v_active = false; return; } } // This is the main horizontal sweep -void isr_start(void) { +void isr_start(void) { // Skip if we're not in the image at all - if(!v_active) { return; } + if (!v_active) { + return; + } // Start Red VGA_R_LOW; VGA_R_HIGH; - // For each "pixel" (really 20 or so screen pixels?) go red or white - for(x=0; x<32; x++) { - if(logo[y/28][x/2]) { - VGA_G_HIGH; - VGA_B_HIGH; - } else { - VGA_G_LOW; - VGA_B_LOW; - } + // For each "pixel", go ON_COLOR or OFF_COLOR + for(x = 0; x < 16; x++) { + // setting the color several times is just an easy way to + // delay, so the image is wider. if you only do the following + // once, you'll be able to make the logo array a lot wider: + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); } } // End of the horizontal line void isr_stop(void) { - if(!v_active) { return; } + if (!v_active) { + return; + } VGA_R_LOW; VGA_G_LOW; VGA_B_LOW; @@ -194,8 +235,11 @@ void isr_update(void) { VGA_H_LOW; } -int main(void) { +__attribute__((constructor)) void premain() { init(); +} + +int main(void) { setup(); while (1) { diff --git a/examples/vga-scope.cpp b/examples/vga-scope.cpp index 0265f9c..9c6dca5 100644 --- a/examples/vga-scope.cpp +++ b/examples/vga-scope.cpp @@ -1,34 +1,90 @@ -// Low-level, non-wirish demonstration of VGA -// -// Connect a microphone or something less to ANALOG_PIN +/* + VGA Oscilloscope demo. + + Connect a microphone or something like it to ANALOG_PIN (0V -- 3.3V + only; 0.2V -- 3.1V will probably look nicer); an attached VGA + monitor will display the signal roughly in real-time. + + The thick blue line corresponds roughly to 0V. + + This is a fairy crude hack, but it's fun to watch/toy around with. + + SerialUSB and SysTick are disabled to get rid of the most frequently + occurring interrupts (which mess with timing). This means that you + have to use perpetual bootloader mode or the reset button to flash + new programs. + + How to wire this to a VGA port: + D6 via ~200ohms to VGA Red (1) + D7 via ~200ohms to VGA Green (2) + D8 via ~200ohms to VGA Blue (3) + D11 to VGA VSync (14) (swapped?) + D12 to VGA HSync (13) (swapped?) + GND to VGA Ground (5) + GND to VGA Sync Ground (10) + + See also: + - http://pinouts.ru/Video/VGA15_pinout.shtml + - http://www.epanorama.net/documents/pc/vga_timing.html + + This code is released into the public domain. + */ #include "wirish.h" +#include "systick.h" + +// FIXME generalize for Native and Mini -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN #define ANALOG_PIN 18 -#define VGA_R 5 // B6 -#define VGA_G 6 // A8 -#define VGA_B 7 // A9 -#define VGA_V 11 // A6 -#define VGA_H 12 // A7 -#define VGA_R_HIGH (GPIOB_BASE)->BSRR = BIT(6) -#define VGA_R_LOW (GPIOB_BASE)->BRR = BIT(6) -#define VGA_G_HIGH (GPIOA_BASE)->BSRR = BIT(8) -#define VGA_G_LOW (GPIOA_BASE)->BRR = BIT(8) -#define VGA_B_HIGH (GPIOA_BASE)->BSRR = BIT(9) -#define VGA_B_LOW (GPIOA_BASE)->BRR = BIT(9) -#define VGA_V_HIGH (GPIOA_BASE)->BSRR = BIT(6) -#define VGA_V_LOW (GPIOA_BASE)->BRR = BIT(6) -#define VGA_H_HIGH (GPIOA_BASE)->BSRR = BIT(7) -#define VGA_H_LOW (GPIOA_BASE)->BRR = BIT(7) + +// Pinouts -- you also must change the GPIO macros below if you change +// these +#define VGA_R 6 // STM32: A8 +#define VGA_G 7 // STM32: A9 +#define VGA_B 8 // STM32: A10 +#define VGA_V 11 // STM32: A6 +#define VGA_H 12 // STM32: A7 + +// These low level (and STM32 specific) macros make GPIO writes much +// faster +#define ABSRR ((volatile uint32*)0x40010810) +#define ABRR ((volatile uint32*)0x40010814) + +#define RBIT 8 // (see pinouts) +#define GBIT 9 +#define BBIT 10 + +#define VGA_R_HIGH *ABSRR = BIT(RBIT) +#define VGA_R_LOW *ABRR = BIT(RBIT) +#define VGA_G_HIGH *ABSRR = BIT(GBIT) +#define VGA_G_LOW *ABRR = BIT(GBIT) +#define VGA_B_HIGH *ABSRR = BIT(BBIT) +#define VGA_B_LOW *ABRR = BIT(BBIT) + +#define COLOR_WHITE (BIT(RBIT) | BIT(GBIT) | BIT(BBIT)) +#define COLOR_BLACK 0 +#define COLOR_RED BIT(RBIT) +#define COLOR_GREEN BIT(GBIT) +#define COLOR_BLUE BIT(BBIT) + +#define BORDER_COLOR COLOR_BLUE + +// set has priority, so clear every bit and set some given bits: +#define VGA_COLOR(c) (*ABSRR = c | \ + BIT(RBIT+16) | BIT(GBIT+16) | BIT(BBIT+16)) + +#define VGA_V_HIGH *ABSRR = BIT(6) +#define VGA_V_LOW *ABRR = BIT(6) +#define VGA_H_HIGH *ABSRR = BIT(7) +#define VGA_H_LOW *ABRR = BIT(7) void isr_porch(void); void isr_start(void); void isr_stop(void); void isr_update(void); -void setup() -{ +void setup() { pinMode(LED_PIN, OUTPUT); pinMode(ANALOG_PIN, INPUT_ANALOG); digitalWrite(LED_PIN, 1); @@ -38,104 +94,104 @@ void setup() pinMode(VGA_V, OUTPUT); pinMode(VGA_H, OUTPUT); - /* Send a message out USART2 */ + // Send a message out USART2 Serial2.begin(9600); - Serial2.println("Video time..."); + Serial2.println("Time to kill the radio star..."); // This gets rid of the majority of the interrupt artifacts; - // a SysTick.end() is required as well + // there's still a glitch for low values of y, but let's not worry + // about that. (Probably due to the hackish way vsync is done). SerialUSB.end(); - + systick_disable(); + digitalWrite(VGA_R, 0); digitalWrite(VGA_G, 0); digitalWrite(VGA_B, 0); - digitalWrite(VGA_H,1); - digitalWrite(VGA_V,1); - - timer_set_prescaler(4,0); - timer_set_mode(4, 1, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 2, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 3, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 4, TIMER_OUTPUTCOMPARE); - timer_set_reload(4, 2287); - timer_set_compare_value(4,1,200); - timer_set_compare_value(4,2,300); - timer_set_compare_value(4,3,2170); // 2219 max... - timer_set_compare_value(4,4,1); - timer_attach_interrupt(4,1,isr_porch); - timer_attach_interrupt(4,2,isr_start); - timer_attach_interrupt(4,3,isr_stop); - timer_attach_interrupt(4,4,isr_update); - - timer_set_count(4,0); + digitalWrite(VGA_H, 1); + digitalWrite(VGA_V, 1); + + timer_pause(TIMER4); + timer_set_prescaler(TIMER4, 0); + timer_set_mode(TIMER4, 1, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 2, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 3, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 4, TIMER_OUTPUTCOMPARE); + timer_set_reload(TIMER4, 2287); + timer_set_compare_value(TIMER4, 1, 200); + timer_set_compare_value(TIMER4, 2, 250); + timer_set_compare_value(TIMER4, 3, 2170); // 2219 max... + timer_set_compare_value(TIMER4, 4, 1); + timer_attach_interrupt(TIMER4, 1, isr_porch); + timer_attach_interrupt(TIMER4, 2, isr_start); + timer_attach_interrupt(TIMER4, 3, isr_stop); + timer_attach_interrupt(TIMER4, 4, isr_update); + + timer_set_count(TIMER4, 0); + timer_resume(TIMER4); } -int toggle = 0; -uint16 x = 0; uint16 y = 0; uint16 val = 0; -uint8 v_active = 1; -GPIO_Port *portb = GPIOB_BASE; +bool v_active = true; +const uint16 x_max = 60; // empirically (and lazily) determined void isr_porch(void) { VGA_H_HIGH; y++; - if(y>=523) { - y=1; - v_active = 1; + val = map(analogRead(ANALOG_PIN), 0, 4095, 0, x_max); + if(y >= 523) { + y = 1; + v_active = true; return; } - if(y>=492) { + if(y >= 492) { VGA_V_HIGH; return; } - if(y>=490) { + if(y >= 490) { VGA_V_LOW; return; } - if(y>=479) { // 479 - v_active = 0; + if(y >= 479) { + v_active = false; return; } } void isr_start(void) { - if(!v_active) { return; } - VGA_R_HIGH; - VGA_R_HIGH; - VGA_R_HIGH; - VGA_R_LOW; - //delayMicroseconds(2); - //gpio_write_bit(GPIOA_BASE, 8, 1); // VGA_G - for(x=0; x<(val>>6); x++) { - } - VGA_B_HIGH; - VGA_G_HIGH; - VGA_G_LOW; - VGA_B_LOW; - //VGA_R_HIGH; - //val = (val + analogRead(ANALOG_PIN))/2; - val = analogRead(ANALOG_PIN); - + if (!v_active) { + return; + } + VGA_COLOR(BORDER_COLOR); + for (int x = 0; x < val; x++) { + VGA_COLOR(COLOR_BLACK); + } + VGA_COLOR(COLOR_WHITE); + VGA_COLOR(COLOR_BLACK); } + void isr_stop(void) { - if(!v_active) { return; } - VGA_R_LOW; - VGA_G_LOW; - VGA_B_LOW; + if (!v_active) { + return; + } + VGA_COLOR(COLOR_BLACK); } + void isr_update(void) { VGA_H_LOW; } void loop() { - //val = analogRead(ANALOG_PIN); + toggleLED(); + delay(100); } +__attribute__((constructor)) void premain() { + init(); +} int main(void) { - init(); setup(); while (1) { diff --git a/wirish/boards.h b/wirish/boards.h index 989eea1..ee93c5a 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -133,7 +133,7 @@ typedef struct PinMapping { /* D23/PC15 */ {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D24/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, /* D25/PD2 */ {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D26/PC10 */ -- cgit v1.2.3 From 4651227fa9f7dece1dd24d2170db16c2e35dc04e Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Wed, 9 Mar 2011 23:25:03 -0500 Subject: Merge refactor into i2c-wip: Squashed commit of the following: commit 4d6662dadfda7f2fd55107535165dc98a0638a3c Merge: 174d9ab 7ddc844 Author: Marti Bolivar Date: Fri Mar 4 23:18:29 2011 -0500 Merge remote branch 'origin/refactor' into refactor commit 174d9ab73cc3387a3812e6f3d3e97519bf5b2150 Author: Marti Bolivar Date: Fri Mar 4 23:16:53 2011 -0500 USBSerial docs fix. commit f217acb73d94f0a88bf33a42684e6e988dcb3685 Author: Marti Bolivar Date: Fri Mar 4 20:25:26 2011 -0500 Brought examples/ up to date; PIN_MAP bugfix for D24. commit c4ba3ba05fc39ef260cd80d91759966952df74ae Author: Marti Bolivar Date: Fri Mar 4 19:16:42 2011 -0500 Cosmetic/documentation changes to adc.c commit e7747b4eb831621951deef6d31629f55cb5c3500 Author: Marti Bolivar Date: Fri Mar 4 19:16:07 2011 -0500 Cosmetic changes to wirish/main.cxx commit e2f9d4116e59d8487c936989384228ea084a3501 Author: Marti Bolivar Date: Fri Mar 4 19:15:24 2011 -0500 Untabifying docs/source/conf.py commit 7ddc84481b4eebe337065a0219e3d8dc000791e5 Author: Perry Hung Date: Wed Mar 2 00:30:19 2011 -0500 cscope: Find .S instead of .s files commit 62cb09ed6357eae58b0234fbc074c44e9c0aa5e5 Author: Marti Bolivar Date: Wed Mar 2 00:07:10 2011 -0500 Fixing typo in main.cpp.example. --- Makefile | 2 +- docs/source/conf.py | 38 +++---- docs/source/lang/api/serialusb.rst | 22 ++-- examples/blinky.cpp | 6 +- examples/debug-dtrrts.cpp | 23 ++-- examples/qa-slave-shield.cpp | 45 ++++---- examples/spi_master.cpp | 7 +- examples/test-bkp.cpp | 2 +- examples/test-dac.cpp | 4 - examples/test-fsmc.cpp | 22 ++-- examples/test-serial-flush.cpp | 18 +--- examples/test-serialusb.cpp | 74 ++++++------- examples/test-systick.cpp | 50 ++++----- examples/test-timers.cpp | 68 ++++++------ examples/vga-leaf.cpp | 162 +++++++++++++++++----------- examples/vga-scope.cpp | 212 +++++++++++++++++++++++-------------- libmaple/adc.c | 4 +- main.cpp.example | 2 +- wirish/boards.h | 2 +- wirish/main.cxx | 9 +- 20 files changed, 420 insertions(+), 352 deletions(-) (limited to 'wirish') diff --git a/Makefile b/Makefile index 149f54a..01e1e72 100644 --- a/Makefile +++ b/Makefile @@ -153,7 +153,7 @@ debug: cscope: rm -rf *.cscope - find . -name '*.[hcs]' -o -name '*.cpp' | xargs cscope -b + find . -name '*.[hcS]' -o -name '*.cpp' | xargs cscope -b tags: etags `find . -name "*.c" -o -name "*.cpp" -o -name "*.h"` diff --git a/docs/source/conf.py b/docs/source/conf.py index 1ad4e57..f232b7c 100644 --- a/docs/source/conf.py +++ b/docs/source/conf.py @@ -117,25 +117,25 @@ html_theme = 'default' # further. For a list of options available for each theme, see the # documentation. html_theme_options = { - ## Sidebar placement options - #'stickysidebar' : 'true', - 'rightsidebar' : 'true', - #'collapsiblesidebar' : 'true', - - ## Color - 'sidebarbgcolor' : '#C8C8C8', - 'sidebarlinkcolor' : 'green', - 'sidebartextcolor' : 'black', + ## Sidebar placement options + #'stickysidebar' : 'true', + 'rightsidebar' : 'true', + #'collapsiblesidebar' : 'true', + + ## Color + 'sidebarbgcolor' : '#C8C8C8', + 'sidebarlinkcolor' : 'green', + 'sidebartextcolor' : 'black', #'sidebarbtncolor' : 'black', - 'footerbgcolor' : 'green', - 'relbarbgcolor' : 'green', - 'headlinkcolor' : '#000000', - 'linkcolor' : 'green', - 'visitedlinkcolor' : 'green', - - ## Font - 'headfont' : 'Georgia', - 'bodyfont' : 'Lucidia' + 'footerbgcolor' : 'green', + 'relbarbgcolor' : 'green', + 'headlinkcolor' : '#000000', + 'linkcolor' : 'green', + 'visitedlinkcolor' : 'green', + + ## Font + 'headfont' : 'Georgia', + 'bodyfont' : 'Lucidia' } # Add any paths that contain custom themes here, relative to this directory. @@ -174,7 +174,7 @@ html_last_updated_fmt = '%b %d, %Y' # re-add commented line when custom template for api finished html_sidebars = { '**': ['globaltoc.html', 'searchbox.html'], - #'lang/api**':['searchbox.html', 'apilist.html'], + #'lang/api**':['searchbox.html', 'apilist.html'], } diff --git a/docs/source/lang/api/serialusb.rst b/docs/source/lang/api/serialusb.rst index 87fa641..4ddfa4a 100644 --- a/docs/source/lang/api/serialusb.rst +++ b/docs/source/lang/api/serialusb.rst @@ -224,7 +224,7 @@ running from battery, or connected but not monitored. You may need to experiment with the DTR/RTS logic for your platform and device configuration. :: - #define LED_PIN 13 + #define LED_PIN BOARD_LED_PIN void setup() { /* Set up the LED to blink */ @@ -232,22 +232,22 @@ configuration. :: } void loop() { - // LED will stay off if we are disconnected; - // will blink quickly if USB is unplugged (battery etc) + // LED will stay off if we are disconnected, and will blink + // quickly if USB is unplugged (battery power, etc.). if(SerialUSB.isConnected()) { digitalWrite(LED_PIN, 1); } delay(100); - // If this logic fails to detect if bytes are going to - // be read by the USB host, then the println() will fully - // many times, causing a very slow LED blink. - // If the characters are printed and read, the blink will - // only slow a small amount when "really" connected, and fast - // when the virtual port is only configured. + // If this logic fails to detect if bytes are going to be read + // by the USB host, then the println() take a long time, + // causing a very slow LED blink. If the characters are + // printed and read, the blink will only slow a small amount + // when "really" connected, and will be fast fast when the + // virtual port is only configured. if(SerialUSB.isConnected() && (SerialUSB.getDTR() || SerialUSB.getRTS())) { - for(int i=0; i<10; i++) { - SerialUSB.println(123456,BIN); + for(int i = 0; i < 10; i++) { + SerialUSB.println(123456, BIN); } } digitalWrite(LED_PIN, 0); diff --git a/examples/blinky.cpp b/examples/blinky.cpp index 5611987..209a6e6 100644 --- a/examples/blinky.cpp +++ b/examples/blinky.cpp @@ -1,4 +1,4 @@ -// Blinks the LED, pin 13 +// Blinks the built-in LED #include "wirish.h" @@ -20,8 +20,8 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } diff --git a/examples/debug-dtrrts.cpp b/examples/debug-dtrrts.cpp index f9f8b96..61c061a 100644 --- a/examples/debug-dtrrts.cpp +++ b/examples/debug-dtrrts.cpp @@ -1,14 +1,12 @@ -// Sample main.cpp file. Blinks an LED, sends a message out USART2 -// and turns on PWM on pin 2 +// Test sketch for figuring out DTR/RTS behavior on different platforms. #include "wirish.h" #include "usb.h" -#define LED_PIN 13 -#define PWM_PIN 2 +#define LED_PIN BOARD_LED_PIN +#define PWM_PIN 2 -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); @@ -18,12 +16,10 @@ void setup() } -int toggle = 0; - void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); + Serial2.print("DTR: "); Serial2.print(usbGetDTR(), DEC); Serial2.print("\tRTS: "); @@ -31,13 +27,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/qa-slave-shield.cpp b/examples/qa-slave-shield.cpp index b395cca..178b780 100644 --- a/examples/qa-slave-shield.cpp +++ b/examples/qa-slave-shield.cpp @@ -1,50 +1,51 @@ -// slave mode for QA shield +// Slave mode for QA shield #include "wirish.h" -#define LED_PIN 13 -#define NUM_GPIO 38 // not the number of the max... +// FIXME generalize for Maple Native, Maple Mini (NUM_GPIO, Mini USB +// breakout pins, etc.) -int i; +#define LED_PIN BOARD_LED_PIN +#define NUM_GPIO 38 // Ignore JTAG pins. -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); - digitalWrite(LED_PIN, 1); + digitalWrite(LED_PIN, HIGH); - for(i=0; i +#include // for snprintf() #include "wirish.h" #include "bkp.h" diff --git a/examples/test-dac.cpp b/examples/test-dac.cpp index 62f40eb..af98030 100644 --- a/examples/test-dac.cpp +++ b/examples/test-dac.cpp @@ -1,8 +1,4 @@ - #include "wirish.h" -#include "fsmc.h" -#include "rcc.h" -#include "gpio.h" #include "dac.h" uint16 count = 0; diff --git a/examples/test-fsmc.cpp b/examples/test-fsmc.cpp index f4fd068..4211e4d 100644 --- a/examples/test-fsmc.cpp +++ b/examples/test-fsmc.cpp @@ -1,14 +1,12 @@ - #include "wirish.h" #include "fsmc.h" -#define LED_PIN 23 // hack for maple native -#define DISC_PIN 14 // hack for USB on native +#define LED_PIN BOARD_LED_PIN // System control block registers #define SCB_BASE (SCB_Reg*)(0xE000ED00) -// This stuff should ultimately get moved to util.h or scb.h or w/e. +// This stuff should ultimately get moved to util.h or scb.h or w/e. // Also in interactive test program and the HardFault IRQ handler. typedef struct { volatile uint32 CPUID; @@ -23,15 +21,14 @@ typedef struct { volatile uint32 SHCRS; volatile uint32 CFSR; volatile uint32 HFSR; - uint32 pad1; + uint32 pad1; volatile uint32 MMAR; volatile uint32 BFAR; } SCB_Reg; -SCB_Reg *scb; +SCB_Reg *scb; uint16 *ptr; -int toggle = 0; int count = 0; void setup() { @@ -39,8 +36,6 @@ void setup() { scb = (SCB_Reg*)SCB_BASE; pinMode(LED_PIN, OUTPUT); - pinMode(DISC_PIN, OUTPUT); - digitalWrite(DISC_PIN,1); digitalWrite(LED_PIN,1); Serial1.begin(9600); @@ -82,15 +77,14 @@ void setup() { Serial1.print("BFAR: "); id = scb->BFAR; Serial1.println(id,BIN); - + Serial1.println("Now testing all memory addresses... (will hardfault at the end)"); delay(3000); } void loop() { - digitalWrite(LED_PIN, toggle); - toggle ^= 1; - delay(1); + toggleLED(); + delay(1); for(int i = 0; i<100; i++) { // modify this to speed things up count++; @@ -102,7 +96,7 @@ void loop() { while(1) { } } } - + Serial1.print((uint32)(ptr),HEX); Serial1.print(": "); Serial1.println(*ptr,BIN); diff --git a/examples/test-serial-flush.cpp b/examples/test-serial-flush.cpp index d7fbf7a..1cd82b6 100644 --- a/examples/test-serial-flush.cpp +++ b/examples/test-serial-flush.cpp @@ -2,22 +2,13 @@ #include "wirish.h" -void setup() -{ +void setup() { /* Send a message out USART2 */ Serial2.begin(9600); Serial2.println("Hello world!"); } -int toggle = 0; - void loop() { - - Serial2.println("This is the first line."); - Serial2.end(); - Serial2.println("This is the second line."); - - Serial2.begin(9600); Serial2.println("Waiting for multiple input..."); while(Serial2.available() < 5) { } Serial2.println(Serial2.read()); @@ -29,13 +20,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-serialusb.cpp b/examples/test-serialusb.cpp index 9d0a862..678c2b9 100644 --- a/examples/test-serialusb.cpp +++ b/examples/test-serialusb.cpp @@ -1,11 +1,10 @@ -// Sample main.cpp file. Blinks an LED, sends a message out USART2 -// and turns on PWM on pin 2 +// Tests SerialUSB functionality. #include "wirish.h" #include "usb.h" -#define LED_PIN 13 -#define BUT_PIN 38 +#define LED_PIN BOARD_LED_PIN +#define BUT_PIN BOARD_BUTTON_PIN uint32 state = 0; #define QUICKPRINT 0 @@ -14,33 +13,29 @@ uint32 state = 0; #define SIMPLE 3 #define ONOFF 4 - -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); /* Set up the Button */ - pinMode(BUT_PIN, INPUT_PULLUP); + pinMode(BUT_PIN, INPUT); Serial2.begin(9600); - Serial2.println("Hello world! This is the debug channel."); -} + Serial2.println("This is the debug channel. Press BUT."); -int toggle = 0; + waitForButtonPress(0); +} uint8 c1 = '-'; void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(1000); - if(digitalRead(BUT_PIN)) { - while(digitalRead(BUT_PIN)) {}; + if(isButtonPressed()) { state++; } - + switch(state) { case QUICKPRINT: for(int i = 0; i<30; i++) { @@ -48,34 +43,34 @@ void loop() { SerialUSB.print('.'); SerialUSB.print('|'); } - Serial2.println(SerialUSB.pending(),DEC); + Serial2.println(SerialUSB.pending(), DEC); SerialUSB.println(); break; case BIGSTUFF: - SerialUSB.println("01234567890123456789012345678901234567890123456789012345678901234567890123456789012345678901234567890"); - SerialUSB.println((uint32)123456789,DEC); + SerialUSB.println("0123456789012345678901234567890123456789" + "0123456789012345678901234567890123456789" + "012345678901234567890"); + SerialUSB.println((int64)123456789, DEC); SerialUSB.println(3.1415926535); - Serial2.println(SerialUSB.pending(),DEC); + Serial2.println(SerialUSB.pending(), DEC); break; case NUMBERS: SerialUSB.println("Numbers! -----------------------------"); Serial2.println("Numbers! -----------------------------"); SerialUSB.println('1'); Serial2.println('1'); - SerialUSB.println(1,DEC); - Serial2.println(1,DEC); - SerialUSB.println(-1,DEC); - Serial2.println(-1,DEC); + SerialUSB.println(1, DEC); + Serial2.println(1, DEC); + SerialUSB.println(-1, DEC); + Serial2.println(-1, DEC); SerialUSB.println(3.14159265); Serial2.println(3.14159265); - SerialUSB.println(3.14159265,9); - Serial2.println(3.14159265,9); - SerialUSB.println(123456789,DEC); - Serial2.println(123456789,DEC); - SerialUSB.println(-123456789,DEC); - Serial2.println(-123456789,DEC); - SerialUSB.println(65535,HEX); - Serial2.println(65535,HEX); + SerialUSB.println(123456789, DEC); + Serial2.println(123456789, DEC); + SerialUSB.println(-123456789, DEC); + Serial2.println(-123456789, DEC); + SerialUSB.println(65535, HEX); + Serial2.println(65535, HEX); break; case SIMPLE: Serial2.println("Trying write('a')"); @@ -92,8 +87,8 @@ void loop() { SerialUSB.print("hij\n\r"); SerialUSB.write(' '); SerialUSB.println(); - Serial2.println("Trying println(123456789,DEC)"); - SerialUSB.println(123456789); + Serial2.println("Trying println(123456789, DEC)"); + SerialUSB.println(123456789, DEC); Serial2.println("Trying println(3.141592)"); SerialUSB.println(3.141592); Serial2.println("Trying println(\"DONE\")"); @@ -103,12 +98,12 @@ void loop() { Serial2.println("Shutting down..."); SerialUSB.println("Shutting down..."); SerialUSB.end(); - Serial2.println("Waiting 4seconds..."); + Serial2.println("Waiting 4 seconds..."); delay(4000); Serial2.println("Starting up..."); SerialUSB.begin(); SerialUSB.println("Hello World!"); - Serial2.println("Waiting 4seconds..."); + Serial2.println("Waiting 4 seconds..."); delay(4000); state++; break; @@ -118,13 +113,12 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-systick.cpp b/examples/test-systick.cpp index 247892d..c7b5529 100644 --- a/examples/test-systick.cpp +++ b/examples/test-systick.cpp @@ -3,54 +3,48 @@ #include "wirish.h" #include "systick.h" -#define LED_PIN 13 -#define PWM_PIN 2 -#define BUT 38 +#define LED_PIN BOARD_LED_PIN +#define PWM_PIN 2 +#define BUT BOARD_BUTTON_PIN -void setup() -{ +void setup() { /* Set up the LED to blink */ pinMode(LED_PIN, OUTPUT); - - /* Turn on PWM on pin PWM_PIN */ - pinMode(PWM_PIN, PWM); - pwmWrite(PWM_PIN, 0x8000); - - pinMode(BUT, INPUT_PULLDOWN); + pinMode(BUT, INPUT); } -int toggle = 0; +bool disable = true; long time = 0; void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + volatile int i = 0; + toggleLED(); // An artificial delay - int16 i = 1; - float j = 1; - for(i=0; i<6553; i++) { - j = sqrt(j) + 1; - } - - if(digitalRead(BUT)) { - systick_disable(); - } else { - systick_resume(); + for(i = 0; i < 150000; i++) + ; + + if(isButtonPressed()) { + if (disable) { + systick_disable(); + SerialUSB.println("Disabling SysTick"); + } else { + SerialUSB.println("Re-enabling SysTick"); + systick_resume(); + } + disable = !disable; } - //SerialUSB.println(micros()); // there is a bug with this SerialUSB.println(millis()); } // Force init to be called *first*, i.e. before static object allocation. // Otherwise, statically allocated object that need libmaple may fail. - __attribute__(( constructor )) void premain() { +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/examples/test-timers.cpp b/examples/test-timers.cpp index ccba251..f3cfdcc 100644 --- a/examples/test-timers.cpp +++ b/examples/test-timers.cpp @@ -2,7 +2,7 @@ #include "wirish.h" -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN void handler1(void); void handler2(void); @@ -12,7 +12,6 @@ void handler4(void); void handler3b(void); void handler4b(void); -int toggle = 0; int t; int count1 = 0; @@ -36,25 +35,24 @@ void setup() pinMode(LED_PIN, OUTPUT); // Setup the button as input - pinMode(38, INPUT_PULLUP); + pinMode(BOARD_BUTTON_PIN, INPUT); - /* Send a message out USART2 */ - //SerialUSB.begin(9600); - SerialUSB.println("Begining timer test..."); + // Wait for user to attach... + waitForButtonPress(0); + + // Send a message out SerialUSB + SerialUSB.println("Beginning timer test..."); for(int t=0; t<4; t++) { Timers[t].setChannel1Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel2Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel3Mode(TIMER_OUTPUTCOMPARE); Timers[t].setChannel4Mode(TIMER_OUTPUTCOMPARE); } - - // Wait for user to attach... - delay(2000); } void loop() { SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setCount/getCount"); + SerialUSB.println("Testing setCount/getCount"); SerialUSB.print("Timer1.getCount() = "); SerialUSB.println(Timer1.getCount()); SerialUSB.println("Timer1.setCount(1234)"); Timer1.setCount(1234); @@ -63,7 +61,7 @@ void loop() { // down Timer4 is in the "pause" state and the timer doesn't increment, so // the final counts should reflect the ratio of time that BUT was held down SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing Pause/Resume; button roughly controls Timer4"); + SerialUSB.println("Testing Pause/Resume; button roughly controls Timer4"); count3 = 0; count4 = 0; Timer3.setChannel1Mode(TIMER_OUTPUTCOMPARE); @@ -80,9 +78,9 @@ void loop() { Timer4.attachCompare1Interrupt(handler4b); Timer3.resume(); Timer4.resume(); - SerialUSB.println("~4 seconds..."); + SerialUSB.println("~4 seconds..."); for(int i = 0; i<4000; i++) { - if(digitalRead(38)) { + if(isButtonPressed()) { Timer4.pause(); } else { Timer4.resume(); @@ -96,14 +94,14 @@ void loop() { // These test the setPeriod auto-configure functionality SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setPeriod"); + SerialUSB.println("Testing setPeriod"); Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); - Timer4.setPeriod(10); + Timer4.setPeriod(10); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 10ms, wait 2 seconds..."); + SerialUSB.println("Period 10ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -114,10 +112,10 @@ void loop() { Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); Timer4.pause(); - Timer4.setPeriod(30000); + Timer4.setPeriod(30000); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -127,12 +125,12 @@ void loop() { SerialUSB.println("(should be around 2sec/30000ms ~ 67)"); Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setPeriod(300000); + Timer4.setPeriod(300000); Timer4.setCompare1(1); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 300000ms, wait 2 seconds..."); + SerialUSB.println("Period 300000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -146,9 +144,9 @@ void loop() { Timer4.setOverflow(65454); Timer4.pause(); Timer4.setCount(0); - Timer4.setCompare1(1); + Timer4.setCompare1(1); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -159,11 +157,11 @@ void loop() { Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); Timer4.setCompare1(1); - Timer4.setPeriod(30000); + Timer4.setPeriod(30000); Timer4.pause(); Timer4.setCount(0); Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + SerialUSB.println("Period 30000ms, wait 2 seconds..."); count4 = 0; Timer4.resume(); delay(2000); @@ -177,7 +175,7 @@ void loop() { // that over time the actual timing rates get blown away by other system // interrupts. for(t=0; t<4; t++) { - toggle ^= 1; digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); SerialUSB.println("-----------------------------------------------------"); SerialUSB.print("Testing Timer "); SerialUSB.println(t+1); @@ -214,33 +212,39 @@ void handler1(void) { val1 += rate1; Timers[t].setCompare1(val1); count1++; -} +} + void handler2(void) { val2 += rate2; Timers[t].setCompare2(val2); count2++; -} +} + void handler3(void) { val3 += rate3; Timers[t].setCompare3(val3); count3++; -} +} + void handler4(void) { val4 += rate4; Timers[t].setCompare4(val4); count4++; -} +} void handler3b(void) { count3++; -} +} + void handler4b(void) { count4++; -} +} +__attribute__((constructor)) void premain() { + init(); +} int main(void) { - init(); setup(); while (1) { diff --git a/examples/vga-leaf.cpp b/examples/vga-leaf.cpp index d1c6d7d..9d9fce2 100644 --- a/examples/vga-leaf.cpp +++ b/examples/vga-leaf.cpp @@ -1,21 +1,21 @@ /* - Crude VGA Output + VGA Output - Outputs a red and white leaf to VGA. This implementation is crude and noisy, - but a fun demo. It should run most VGA monitors at 640x480, though it does - not follow the timing spec very carefully. Real twisted or shielded wires, - proper grounding, and not doing this on a breadboard are recommended (but - it seems to work ok without). + Outputs a red and white leaf to VGA. It should run most VGA monitors + at 640x480, though it does not follow the timing spec very + carefully. Real twisted or shielded wires, proper grounding, and not + doing this on a breadboard are recommended (but it seems to work ok + without). - SerialUSB is disabled to get rid of most interrupts (which mess with timing); - the SysTick is probably the source of the remaining flickers. This means that - you have to use perpetual bootloader or the reset button to flash new - programs. + SerialUSB and SysTick are disabled to get rid of the most frequently + occurring interrupts (which mess with timing). This means that you + have to use perpetual bootloader mode or the reset button to flash + new programs. How to wire this to a VGA port: - D5 via ~200ohms to VGA Red (1) - D6 via ~200ohms to VGA Green (2) - D7 via ~200ohms to VGA Blue (3) + D6 via ~200ohms to VGA Red (1) + D7 via ~200ohms to VGA Green (2) + D8 via ~200ohms to VGA Blue (3) D11 to VGA VSync (14) (swapped?) D12 to VGA HSync (13) (swapped?) GND to VGA Ground (5) @@ -24,48 +24,71 @@ See also: - http://pinouts.ru/Video/VGA15_pinout.shtml - http://www.epanorama.net/documents/pc/vga_timing.html - + Created 20 July 2010 By Bryan Newbold for LeafLabs This code is released with no strings attached. - + + Modified 4 March 2011 + By Marti Bolivar + Disabled SysTick, kept up-to-date with libmaple. */ +// FIXME: generalize for Native and Mini + #include "wirish.h" -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN -// Pinouts -#define VGA_R 5 // STM32: B6 -#define VGA_G 6 // STM32: A8 -#define VGA_B 7 // STM32: A9 +// Pinouts -- you also must change the GPIO macros below if you change +// these +#define VGA_R 6 // STM32: A8 +#define VGA_G 7 // STM32: A9 +#define VGA_B 8 // STM32: A10 #define VGA_V 11 // STM32: A6 #define VGA_H 12 // STM32: A7 -// These low level macros make GPIO writes much faster -#define VGA_R_HIGH (GPIOB_BASE)->BSRR = BIT(6) -#define VGA_R_LOW (GPIOB_BASE)->BRR = BIT(6) -#define VGA_G_HIGH (GPIOA_BASE)->BSRR = BIT(8) -#define VGA_G_LOW (GPIOA_BASE)->BRR = BIT(8) -#define VGA_B_HIGH (GPIOA_BASE)->BSRR = BIT(9) -#define VGA_B_LOW (GPIOA_BASE)->BRR = BIT(9) -#define VGA_V_HIGH (GPIOA_BASE)->BSRR = BIT(6) -#define VGA_V_LOW (GPIOA_BASE)->BRR = BIT(6) -#define VGA_H_HIGH (GPIOA_BASE)->BSRR = BIT(7) -#define VGA_H_LOW (GPIOA_BASE)->BRR = BIT(7) +// These low level (and STM32 specific) macros make GPIO writes much +// faster +#define ABSRR ((volatile uint32*)0x40010810) +#define ABRR ((volatile uint32*)0x40010814) + +#define RBIT 8 // (see pinouts) +#define GBIT 9 +#define BBIT 10 + +#define VGA_R_HIGH *ABSRR = BIT(RBIT) +#define VGA_R_LOW *ABRR = BIT(RBIT) +#define VGA_G_HIGH *ABSRR = BIT(GBIT) +#define VGA_G_LOW *ABRR = BIT(GBIT) +#define VGA_B_HIGH *ABSRR = BIT(BBIT) +#define VGA_B_LOW *ABRR = BIT(BBIT) + +#define ON_COLOR BIT(RBIT) +#define OFF_COLOR (BIT(RBIT) | BIT(GBIT) | BIT(BBIT)) + +// set has priority, so clear every bit and set some given bits: +#define VGA_COLOR(c) (*ABSRR = c | \ + BIT(RBIT+16) | BIT(GBIT+16) | BIT(BBIT+16)) + +#define VGA_V_HIGH *ABSRR = BIT(6) +#define VGA_V_LOW *ABRR = BIT(6) +#define VGA_H_HIGH *ABSRR = BIT(7) +#define VGA_H_LOW *ABRR = BIT(7) void isr_porch(void); void isr_start(void); void isr_stop(void); void isr_update(void); -uint8 toggle; uint16 x = 0; // X coordinate uint16 y = 0; // Y coordinate -uint8 v_active = 1; // Are we in the image? +uint16 logo_y = 0; // Y coordinate, mapped into valid logo index (for speed) +bool v_active = true; // Are we in the image? -// 1-bit! -uint8 logo[18][16] = { +const uint8 x_max = 16; +const uint8 y_max = 18; +uint32 logo[y_max][x_max] = { {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,}, {0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,}, {0,0,0,0,0,1,0,0,0,1,0,0,0,0,0,0,}, @@ -99,9 +122,20 @@ void setup() { digitalWrite(VGA_H, HIGH); digitalWrite(VGA_V, HIGH); + // Fill the logo array with color patterns corresponding to its + // truth value. Note that we could get more tricky here, since + // there are 3 bits of color. + for (int y = 0; y < y_max; y++) { + for (int x = 0; x < x_max; x++) { + logo[y][x] = logo[y][x] ? ON_COLOR : OFF_COLOR; + } + } + // This gets rid of the majority of the interrupt artifacts; + // there's still a glitch for low values of y, but let's not worry + // about that. (Probably due to the hackish way vsync is done). SerialUSB.end(); - SystemTick.end(); + systick_disable(); // Configure Timer4.pause(); // while we configure @@ -120,14 +154,13 @@ void setup() { Timer4.attachCompare3Interrupt(isr_stop); Timer4.setCompare4(1); // Could be zero I guess Timer4.attachCompare4Interrupt(isr_update); - + Timer4.setCount(0); // Ready... Timer4.resume(); // Go! } void loop() { - toggle ^= 1; - digitalWrite(LED_PIN, toggle); + toggleLED(); delay(100); // Everything happens in the interrupts! @@ -139,51 +172,59 @@ void loop() { void isr_porch(void) { VGA_H_HIGH; y++; + logo_y = map(y, 0, 478, 0, y_max); // Back to the top - if(y>=523) { - y=1; - v_active = 1; + if(y >= 523) { + y = 1; + logo_y = 0; + v_active = true; return; } // Other vsync stuff below the image - if(y>=492) { + if(y >= 492) { VGA_V_HIGH; return; } - if(y>=490) { + if(y >= 490) { VGA_V_LOW; return; } - if(y>=479) { - v_active = 0; + if(y >= 479) { + v_active = false; return; } } // This is the main horizontal sweep -void isr_start(void) { +void isr_start(void) { // Skip if we're not in the image at all - if(!v_active) { return; } + if (!v_active) { + return; + } // Start Red VGA_R_LOW; VGA_R_HIGH; - // For each "pixel" (really 20 or so screen pixels?) go red or white - for(x=0; x<32; x++) { - if(logo[y/28][x/2]) { - VGA_G_HIGH; - VGA_B_HIGH; - } else { - VGA_G_LOW; - VGA_B_LOW; - } + // For each "pixel", go ON_COLOR or OFF_COLOR + for(x = 0; x < 16; x++) { + // setting the color several times is just an easy way to + // delay, so the image is wider. if you only do the following + // once, you'll be able to make the logo array a lot wider: + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); + VGA_COLOR(logo[logo_y][x]); } } // End of the horizontal line void isr_stop(void) { - if(!v_active) { return; } + if (!v_active) { + return; + } VGA_R_LOW; VGA_G_LOW; VGA_B_LOW; @@ -194,8 +235,11 @@ void isr_update(void) { VGA_H_LOW; } -int main(void) { +__attribute__((constructor)) void premain() { init(); +} + +int main(void) { setup(); while (1) { diff --git a/examples/vga-scope.cpp b/examples/vga-scope.cpp index 0265f9c..9c6dca5 100644 --- a/examples/vga-scope.cpp +++ b/examples/vga-scope.cpp @@ -1,34 +1,90 @@ -// Low-level, non-wirish demonstration of VGA -// -// Connect a microphone or something less to ANALOG_PIN +/* + VGA Oscilloscope demo. + + Connect a microphone or something like it to ANALOG_PIN (0V -- 3.3V + only; 0.2V -- 3.1V will probably look nicer); an attached VGA + monitor will display the signal roughly in real-time. + + The thick blue line corresponds roughly to 0V. + + This is a fairy crude hack, but it's fun to watch/toy around with. + + SerialUSB and SysTick are disabled to get rid of the most frequently + occurring interrupts (which mess with timing). This means that you + have to use perpetual bootloader mode or the reset button to flash + new programs. + + How to wire this to a VGA port: + D6 via ~200ohms to VGA Red (1) + D7 via ~200ohms to VGA Green (2) + D8 via ~200ohms to VGA Blue (3) + D11 to VGA VSync (14) (swapped?) + D12 to VGA HSync (13) (swapped?) + GND to VGA Ground (5) + GND to VGA Sync Ground (10) + + See also: + - http://pinouts.ru/Video/VGA15_pinout.shtml + - http://www.epanorama.net/documents/pc/vga_timing.html + + This code is released into the public domain. + */ #include "wirish.h" +#include "systick.h" + +// FIXME generalize for Native and Mini -#define LED_PIN 13 +#define LED_PIN BOARD_LED_PIN #define ANALOG_PIN 18 -#define VGA_R 5 // B6 -#define VGA_G 6 // A8 -#define VGA_B 7 // A9 -#define VGA_V 11 // A6 -#define VGA_H 12 // A7 -#define VGA_R_HIGH (GPIOB_BASE)->BSRR = BIT(6) -#define VGA_R_LOW (GPIOB_BASE)->BRR = BIT(6) -#define VGA_G_HIGH (GPIOA_BASE)->BSRR = BIT(8) -#define VGA_G_LOW (GPIOA_BASE)->BRR = BIT(8) -#define VGA_B_HIGH (GPIOA_BASE)->BSRR = BIT(9) -#define VGA_B_LOW (GPIOA_BASE)->BRR = BIT(9) -#define VGA_V_HIGH (GPIOA_BASE)->BSRR = BIT(6) -#define VGA_V_LOW (GPIOA_BASE)->BRR = BIT(6) -#define VGA_H_HIGH (GPIOA_BASE)->BSRR = BIT(7) -#define VGA_H_LOW (GPIOA_BASE)->BRR = BIT(7) + +// Pinouts -- you also must change the GPIO macros below if you change +// these +#define VGA_R 6 // STM32: A8 +#define VGA_G 7 // STM32: A9 +#define VGA_B 8 // STM32: A10 +#define VGA_V 11 // STM32: A6 +#define VGA_H 12 // STM32: A7 + +// These low level (and STM32 specific) macros make GPIO writes much +// faster +#define ABSRR ((volatile uint32*)0x40010810) +#define ABRR ((volatile uint32*)0x40010814) + +#define RBIT 8 // (see pinouts) +#define GBIT 9 +#define BBIT 10 + +#define VGA_R_HIGH *ABSRR = BIT(RBIT) +#define VGA_R_LOW *ABRR = BIT(RBIT) +#define VGA_G_HIGH *ABSRR = BIT(GBIT) +#define VGA_G_LOW *ABRR = BIT(GBIT) +#define VGA_B_HIGH *ABSRR = BIT(BBIT) +#define VGA_B_LOW *ABRR = BIT(BBIT) + +#define COLOR_WHITE (BIT(RBIT) | BIT(GBIT) | BIT(BBIT)) +#define COLOR_BLACK 0 +#define COLOR_RED BIT(RBIT) +#define COLOR_GREEN BIT(GBIT) +#define COLOR_BLUE BIT(BBIT) + +#define BORDER_COLOR COLOR_BLUE + +// set has priority, so clear every bit and set some given bits: +#define VGA_COLOR(c) (*ABSRR = c | \ + BIT(RBIT+16) | BIT(GBIT+16) | BIT(BBIT+16)) + +#define VGA_V_HIGH *ABSRR = BIT(6) +#define VGA_V_LOW *ABRR = BIT(6) +#define VGA_H_HIGH *ABSRR = BIT(7) +#define VGA_H_LOW *ABRR = BIT(7) void isr_porch(void); void isr_start(void); void isr_stop(void); void isr_update(void); -void setup() -{ +void setup() { pinMode(LED_PIN, OUTPUT); pinMode(ANALOG_PIN, INPUT_ANALOG); digitalWrite(LED_PIN, 1); @@ -38,104 +94,104 @@ void setup() pinMode(VGA_V, OUTPUT); pinMode(VGA_H, OUTPUT); - /* Send a message out USART2 */ + // Send a message out USART2 Serial2.begin(9600); - Serial2.println("Video time..."); + Serial2.println("Time to kill the radio star..."); // This gets rid of the majority of the interrupt artifacts; - // a SysTick.end() is required as well + // there's still a glitch for low values of y, but let's not worry + // about that. (Probably due to the hackish way vsync is done). SerialUSB.end(); - + systick_disable(); + digitalWrite(VGA_R, 0); digitalWrite(VGA_G, 0); digitalWrite(VGA_B, 0); - digitalWrite(VGA_H,1); - digitalWrite(VGA_V,1); - - timer_set_prescaler(4,0); - timer_set_mode(4, 1, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 2, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 3, TIMER_OUTPUTCOMPARE); - timer_set_mode(4, 4, TIMER_OUTPUTCOMPARE); - timer_set_reload(4, 2287); - timer_set_compare_value(4,1,200); - timer_set_compare_value(4,2,300); - timer_set_compare_value(4,3,2170); // 2219 max... - timer_set_compare_value(4,4,1); - timer_attach_interrupt(4,1,isr_porch); - timer_attach_interrupt(4,2,isr_start); - timer_attach_interrupt(4,3,isr_stop); - timer_attach_interrupt(4,4,isr_update); - - timer_set_count(4,0); + digitalWrite(VGA_H, 1); + digitalWrite(VGA_V, 1); + + timer_pause(TIMER4); + timer_set_prescaler(TIMER4, 0); + timer_set_mode(TIMER4, 1, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 2, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 3, TIMER_OUTPUTCOMPARE); + timer_set_mode(TIMER4, 4, TIMER_OUTPUTCOMPARE); + timer_set_reload(TIMER4, 2287); + timer_set_compare_value(TIMER4, 1, 200); + timer_set_compare_value(TIMER4, 2, 250); + timer_set_compare_value(TIMER4, 3, 2170); // 2219 max... + timer_set_compare_value(TIMER4, 4, 1); + timer_attach_interrupt(TIMER4, 1, isr_porch); + timer_attach_interrupt(TIMER4, 2, isr_start); + timer_attach_interrupt(TIMER4, 3, isr_stop); + timer_attach_interrupt(TIMER4, 4, isr_update); + + timer_set_count(TIMER4, 0); + timer_resume(TIMER4); } -int toggle = 0; -uint16 x = 0; uint16 y = 0; uint16 val = 0; -uint8 v_active = 1; -GPIO_Port *portb = GPIOB_BASE; +bool v_active = true; +const uint16 x_max = 60; // empirically (and lazily) determined void isr_porch(void) { VGA_H_HIGH; y++; - if(y>=523) { - y=1; - v_active = 1; + val = map(analogRead(ANALOG_PIN), 0, 4095, 0, x_max); + if(y >= 523) { + y = 1; + v_active = true; return; } - if(y>=492) { + if(y >= 492) { VGA_V_HIGH; return; } - if(y>=490) { + if(y >= 490) { VGA_V_LOW; return; } - if(y>=479) { // 479 - v_active = 0; + if(y >= 479) { + v_active = false; return; } } void isr_start(void) { - if(!v_active) { return; } - VGA_R_HIGH; - VGA_R_HIGH; - VGA_R_HIGH; - VGA_R_LOW; - //delayMicroseconds(2); - //gpio_write_bit(GPIOA_BASE, 8, 1); // VGA_G - for(x=0; x<(val>>6); x++) { - } - VGA_B_HIGH; - VGA_G_HIGH; - VGA_G_LOW; - VGA_B_LOW; - //VGA_R_HIGH; - //val = (val + analogRead(ANALOG_PIN))/2; - val = analogRead(ANALOG_PIN); - + if (!v_active) { + return; + } + VGA_COLOR(BORDER_COLOR); + for (int x = 0; x < val; x++) { + VGA_COLOR(COLOR_BLACK); + } + VGA_COLOR(COLOR_WHITE); + VGA_COLOR(COLOR_BLACK); } + void isr_stop(void) { - if(!v_active) { return; } - VGA_R_LOW; - VGA_G_LOW; - VGA_B_LOW; + if (!v_active) { + return; + } + VGA_COLOR(COLOR_BLACK); } + void isr_update(void) { VGA_H_LOW; } void loop() { - //val = analogRead(ANALOG_PIN); + toggleLED(); + delay(100); } +__attribute__((constructor)) void premain() { + init(); +} int main(void) { - init(); setup(); while (1) { diff --git a/libmaple/adc.c b/libmaple/adc.c index cd71118..a464746 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -23,6 +23,8 @@ *****************************************************************************/ /** + * @file adc.c + * * @brief Analog to digital converter routines * * IMPORTANT: maximum external impedance must be below 0.4kOhms for 1.5 @@ -30,7 +32,7 @@ * * At 55.5 cycles/sample, the external input impedance < 50kOhms. * - * See stm32 manual RM008 for how to calculate this. + * See STM32 manual RM0008 for how to calculate this. */ #include "libmaple.h" diff --git a/main.cpp.example b/main.cpp.example index 8fc522a..3ae114b 100644 --- a/main.cpp.example +++ b/main.cpp.example @@ -27,7 +27,7 @@ void loop() { } // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. +// Otherwise, statically allocated objects that need libmaple may fail. __attribute__(( constructor )) void premain() { init(); } diff --git a/wirish/boards.h b/wirish/boards.h index 989eea1..ee93c5a 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -133,7 +133,7 @@ typedef struct PinMapping { /* D23/PC15 */ {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, /* D24/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, + {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, /* D25/PD2 */ {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, /* D26/PC10 */ diff --git a/wirish/main.cxx b/wirish/main.cxx index f0158f8..dd5e296 100644 --- a/wirish/main.cxx +++ b/wirish/main.cxx @@ -1,4 +1,4 @@ -/* ***************************************************************************** +/****************************************************************************** * The MIT License * * Copyright (c) 2010 LeafLabs LLC. @@ -20,16 +20,15 @@ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * THE SOFTWARE. - * ****************************************************************************/ + *****************************************************************************/ // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. +// Otherwise, statically allocated objects that need libmaple may fail. __attribute__(( constructor )) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { -- cgit v1.2.3 From 9872b3975bd40c55652bb9dead5f54e2be9740d0 Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Thu, 10 Mar 2011 00:04:58 -0500 Subject: Fix merge error and compile error. --- libmaple/delay.h | 22 +++++++ libmaple/i2c.c | 168 ++++++++++++---------------------------------------- libmaple/i2c.h | 116 ++++++++++++++++++++++++++++-------- libmaple/libmaple.h | 2 + libmaple/rcc.c | 2 +- libmaple/stm32.h | 10 ++++ main.cpp | 28 ++++++--- wirish/time.c | 13 +--- 8 files changed, 186 insertions(+), 175 deletions(-) create mode 100644 libmaple/delay.h (limited to 'wirish') diff --git a/libmaple/delay.h b/libmaple/delay.h new file mode 100644 index 0000000..10839c9 --- /dev/null +++ b/libmaple/delay.h @@ -0,0 +1,22 @@ +/** + * @brief + */ + +#ifndef _DELAY_H_ +#define _DELAY_H_ + +static inline void delay_us(uint32 us) { + /* So (2^32)/12 micros max, or less than 6 minutes */ + us *= 12; + + /* fudge for function call overhead */ + us--; + asm volatile(" mov r0, %[us] \n\t" + "1: subs r0, #1 \n\t" + " bhi 1b \n\t" + : + : [us] "r" (us) + : "r0"); +} +#endif + diff --git a/libmaple/i2c.c b/libmaple/i2c.c index 1a595f5..3e948f6 100644 --- a/libmaple/i2c.c +++ b/libmaple/i2c.c @@ -39,11 +39,12 @@ /* 2/17 Started 10pm-4am * 2/19 Started 7pm-2am * 2/20 Started 7pm-7pm - * 2/23 Started 8pm */ + * 2/23 Started 8pm-8am + * 3/9 Started 11pm */ static inline int32 wait_for_state_change(i2c_dev *dev, i2c_state state); -i2c_dev i2c_dev1 = { +static i2c_dev i2c_dev1 = { .regs = (i2c_reg_map*)I2C1_BASE, .gpio_port = GPIOB_BASE, .sda_pin = 7, @@ -54,30 +55,13 @@ i2c_dev i2c_dev1 = { .state = I2C_STATE_IDLE }; +i2c_dev* const I2C1 = &i2c_dev1; + /** * @brief IRQ handler for i2c master. Handles transmission/reception. * @param dev i2c device */ -void delay_us(uint32 us) { - /* So (2^32)/12 micros max, or less than 6 minutes */ - us *= 12; - - /* fudge for function call overhead */ - us--; - asm volatile(" mov r0, %[us] \n\t" - "1: subs r0, #1 \n\t" - " bhi 1b \n\t" - : - : [us] "r" (us) - : "r0"); -} -static inline void debug_toggle(uint32 delay) { - gpio_write_bit(GPIOA_BASE, 5, 1); - delay_us(delay); - gpio_write_bit(GPIOA_BASE, 5, 0); -} - struct crumb { uint32 event; uint32 sr1; @@ -125,15 +109,15 @@ static void i2c_irq_handler(i2c_dev *dev) { */ if (sr1 & I2C_SR1_SB) { msg->xferred = 0; - i2c_enable_irq(dev->regs, I2C_IRQ_BUFFER); + i2c_enable_irq(dev, I2C_IRQ_BUFFER); /* * Master receiver */ if (read) { - i2c_enable_ack(dev->regs); + i2c_enable_ack(dev); } - i2c_send_slave_addr(dev->regs, msg->addr, read); + i2c_send_slave_addr(dev, msg->addr, read); sr1 = sr2 = 0; } @@ -148,13 +132,13 @@ static void i2c_irq_handler(i2c_dev *dev) { */ if (read) { if (msg->length == 1) { - i2c_disable_ack(dev->regs); + i2c_disable_ack(dev); dev->msgs_left--; if (dev->msgs_left) { - i2c_start_condition(dev->regs); + i2c_start_condition(dev); leave_big_crumb(RX_ADDR_START, 0, 0); } else { - i2c_stop_condition(dev->regs); + i2c_stop_condition(dev); leave_big_crumb(RX_ADDR_STOP, 0, 0); } } @@ -163,7 +147,7 @@ static void i2c_irq_handler(i2c_dev *dev) { * Master transmitter: write first byte to fill shift register. * We should get another TXE interrupt immediately to fill DR again. */ - i2c_write(dev->regs, msg->data[msg->xferred++]); + i2c_write(dev, msg->data[msg->xferred++]); } sr1 = sr2 = 0; } @@ -176,13 +160,13 @@ static void i2c_irq_handler(i2c_dev *dev) { if ((sr1 & I2C_SR1_TXE) && !(sr1 & I2C_SR1_BTF)) { leave_big_crumb(TXE_ONLY, 0, 0); if (dev->msgs_left) { - i2c_write(dev->regs, msg->data[msg->xferred++]); + i2c_write(dev, msg->data[msg->xferred++]); if (msg->xferred == msg->length) { /* * End of this message. Turn off TXE/RXNE and wait for * BTF to send repeated start or stop condition. */ - i2c_disable_irq(dev->regs, I2C_IRQ_BUFFER); + i2c_disable_irq(dev, I2C_IRQ_BUFFER); dev->msgs_left--; } } else { @@ -207,18 +191,21 @@ static void i2c_irq_handler(i2c_dev *dev) { * won't interrupt, but if we don't disable ITEVTEN, BTF will * continually interrupt us. What the fuck ST? */ - i2c_start_condition(dev->regs); + i2c_start_condition(dev); while (!(dev->regs->SR1 & I2C_SR1_SB)) ; dev->msg++; } else { - i2c_stop_condition(dev->regs); + i2c_stop_condition(dev); +// while (dev->regs->CR1 & I2C_CR1_STOP) { +// ; +// } /* * Turn off event interrupts to keep BTF from firing until the end * of the stop condition. Why on earth they didn't have a start/stop * condition request clear BTF is beyond me. */ - i2c_disable_irq(dev->regs, I2C_IRQ_EVENT); + i2c_disable_irq(dev, I2C_IRQ_EVENT); leave_big_crumb(STOP_SENT, 0, 0); dev->state = I2C_STATE_XFER_DONE; } @@ -238,12 +225,12 @@ static void i2c_irq_handler(i2c_dev *dev) { * RXNE interrupt before shutting things down. */ if (msg->xferred == (msg->length - 1)) { - i2c_disable_ack(dev->regs); + i2c_disable_ack(dev); if (dev->msgs_left > 2) { - i2c_start_condition(dev->regs); + i2c_start_condition(dev); leave_big_crumb(RXNE_START_SENT, 0, 0); } else { - i2c_stop_condition(dev->regs); + i2c_stop_condition(dev); leave_big_crumb(RXNE_STOP_SENT, 0, 0); } } else if (msg->xferred == msg->length) { @@ -262,11 +249,18 @@ static void i2c_irq_handler(i2c_dev *dev) { } void __irq_i2c1_ev(void) { - i2c_dev *dev = I2C1; - i2c_irq_handler(dev); + i2c_irq_handler(&i2c_dev1); +} + +static void i2c_irq_error_handler(i2c_dev *dev) { + __error(); } -static void i2c_bus_reset(i2c_dev *dev) { +void __irq_i2c1_er(void) { + i2c_irq_error_handler(&i2c_dev1); +} + +static void i2c_bus_reset(const i2c_dev *dev) { /* Release both lines */ gpio_write_bit(dev->gpio_port, dev->scl_pin, 1); gpio_write_bit(dev->gpio_port, dev->sda_pin, 1); @@ -322,21 +316,21 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { gpio_set_mode(dev->gpio_port, dev->scl_pin, GPIO_MODE_AF_OUTPUT_OD); /* I2C1 and I2C2 are fed from APB1, clocked at 36MHz */ - i2c_set_input_clk(dev->regs, 36); + i2c_set_input_clk(dev, 36); /* 100 khz only for now */ - i2c_set_clk_control(dev->regs, STANDARD_CCR); + i2c_set_clk_control(dev, STANDARD_CCR); /* * Set scl rise time, standard mode for now. * Max rise time in standard mode: 1000 ns * Max rise time in fast mode: 300ns */ - i2c_set_trise(dev->regs, STANDARD_TRISE); + i2c_set_trise(dev, STANDARD_TRISE); /* Enable event and buffer interrupts */ nvic_irq_enable(dev->ev_nvic_line); - i2c_enable_irq(dev->regs, I2C_IRQ_EVENT | I2C_IRQ_BUFFER); + i2c_enable_irq(dev, I2C_IRQ_EVENT | I2C_IRQ_BUFFER); /* * Important STM32 Errata: @@ -368,13 +362,12 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { nvic_irq_set_priority(dev->ev_nvic_line, 0); /* Make it go! */ - i2c_peripheral_enable(dev->regs); + i2c_peripheral_enable(dev); } int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num) { int32 rc; - static int times = 0; dev->msg = msgs; dev->msgs_left = num; @@ -389,7 +382,7 @@ int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num) { dev->state = I2C_STATE_BUSY; - i2c_start_condition(dev->regs); + i2c_start_condition(dev); rc = wait_for_state_change(dev, I2C_STATE_XFER_DONE); if (rc < 0) { goto out; @@ -414,89 +407,6 @@ static inline int32 wait_for_state_change(i2c_dev *dev, i2c_state state) { } -/* - * Low level register twiddling functions - */ - -/** - * @brief turn on an i2c peripheral - * @param map i2c peripheral register base - */ -void i2c_peripheral_enable(i2c_reg_map *regs) { - regs->CR1 |= I2C_CR1_PE; -} - -/** - * @brief turn off an i2c peripheral - * @param map i2c peripheral register base - */ -void i2c_peripheral_disable(i2c_reg_map *regs) { - regs->CR1 &= ~I2C_CR1_PE; -} - -/** - * @brief Set input clock frequency, in mhz - * @param device to configure - * @param freq frequency in megahertz (2-36) - */ -void i2c_set_input_clk(i2c_reg_map *regs, uint32 freq) { - uint32 cr2 = regs->CR2; - cr2 &= ~I2C_CR2_FREQ; - cr2 |= freq; - regs->CR2 = freq; -} - -void i2c_set_clk_control(i2c_reg_map *regs, uint32 val) { - uint32 ccr = regs->CCR; - ccr &= ~I2C_CCR_CCR; - ccr |= val; - regs->CCR = ccr; -} - -void i2c_set_fast_mode(i2c_reg_map *regs) { - regs->CCR |= I2C_CCR_FS; -} - -void i2c_set_standard_mode(i2c_reg_map *regs) { - regs->CCR &= ~I2C_CCR_FS; -} - -/** - * @brief Set SCL rise time - * @param - */ - -void i2c_set_trise(i2c_reg_map *regs, uint32 trise) { - regs->TRISE = trise; -} - -void i2c_start_condition(i2c_reg_map *regs) { - regs->CR1 |= I2C_CR1_START; -} - -void i2c_stop_condition(i2c_reg_map *regs) { - regs->CR1 |= I2C_CR1_STOP; -} - -void i2c_send_slave_addr(i2c_reg_map *regs, uint32 addr, uint32 rw) { - regs->DR = (addr << 1) | rw; -} - -void i2c_enable_irq(i2c_reg_map *regs, uint32 irqs) { - regs->CR2 |= irqs; -} - -void i2c_disable_irq(i2c_reg_map *regs, uint32 irqs) { - regs->CR2 &= ~irqs; -} - -void i2c_enable_ack(i2c_reg_map *regs) { - regs->CR1 |= I2C_CR1_ACK; -} - -void i2c_disable_ack(i2c_reg_map *regs) { - regs->CR1 &= ~I2C_CR1_ACK; -} diff --git a/libmaple/i2c.h b/libmaple/i2c.h index 2e6d00d..be05615 100644 --- a/libmaple/i2c.h +++ b/libmaple/i2c.h @@ -72,14 +72,10 @@ typedef struct i2c_dev { } i2c_dev; -extern i2c_dev i2c_dev1; -extern i2c_dev i2c_dev2; +extern i2c_dev* const I2C1; -#define I2C1 (i2c_dev*)&i2c_dev1 -#define I2C2 (i2c_dev*)&i2c_dev2 - -#define I2C1_BASE 0x40005400 -#define I2C2_BASE 0x40005800 +#define I2C1_BASE (i2c_reg_map*)0x40005400 +#define I2C2_BASE (i2c_reg_map*)0x40005800 /* i2c enable options */ #define I2C_FAST_MODE 0x1 // 400 khz @@ -140,28 +136,98 @@ extern "C" { void i2c_master_enable(i2c_dev *dev, uint32 flags); int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num); -void i2c_start_condition(i2c_reg_map *regs); -void i2c_stop_condition(i2c_reg_map *regs); -void i2c_send_slave_addr(i2c_reg_map *regs, uint32 addr, uint32 rw); -void i2c_set_input_clk(i2c_reg_map *regs, uint32 freq); -void i2c_set_clk_control(i2c_reg_map *regs, uint32 val); -void i2c_set_fast_mode(i2c_reg_map *regs); -void i2c_set_standard_mode(i2c_reg_map *regs); -void i2c_set_trise(i2c_reg_map *regs, uint32 trise); -void i2c_enable_ack(i2c_reg_map *regs); -void i2c_disable_ack(i2c_reg_map *regs); - -/* interrupt flags */ +static inline void i2c_write(i2c_dev *dev, uint8 byte) { + dev->regs->DR = byte; +} + +/* + * Low level register twiddling functions + */ + +/** + * @brief turn on an i2c peripheral + * @param map i2c peripheral register base + */ +static inline void i2c_peripheral_enable(i2c_dev *dev) { + dev->regs->CR1 |= I2C_CR1_PE; +} + +/** + * @brief turn off an i2c peripheral + * @param map i2c peripheral register base + */ +static inline void i2c_peripheral_disable(i2c_dev *dev) { + dev->regs->CR1 &= ~I2C_CR1_PE; +} + +/** + * @brief Set input clock frequency, in mhz + * @param device to configure + * @param freq frequency in megahertz (2-36) + */ +static inline void i2c_set_input_clk(i2c_dev *dev, uint32 freq) { + uint32 cr2 = dev->regs->CR2; + cr2 &= ~I2C_CR2_FREQ; + cr2 |= freq; + dev->regs->CR2 = freq; +} + +static inline void i2c_set_clk_control(i2c_dev *dev, uint32 val) { + uint32 ccr = dev->regs->CCR; + ccr &= ~I2C_CCR_CCR; + ccr |= val; + dev->regs->CCR = ccr; +} + +static inline void i2c_set_fast_mode(i2c_dev *dev) { + dev->regs->CCR |= I2C_CCR_FS; +} + +static inline void i2c_set_standard_mode(i2c_dev *dev) { + dev->regs->CCR &= ~I2C_CCR_FS; +} + +/** + * @brief Set SCL rise time + * @param + */ +static inline void i2c_set_trise(i2c_dev *dev, uint32 trise) { + dev->regs->TRISE = trise; +} + +extern void toggle(void); +static inline void i2c_start_condition(i2c_dev *dev) { + uint32 cr1 = dev->regs->CR1; +// if (cr1 & (I2C_CR1_START | I2C_CR1_STOP | I2C_CR1_PEC)) { +// } + dev->regs->CR1 |= I2C_CR1_START; +} + +static inline void i2c_stop_condition(i2c_dev *dev) { + dev->regs->CR1 |= I2C_CR1_STOP; +} + +static inline void i2c_send_slave_addr(i2c_dev *dev, uint32 addr, uint32 rw) { + dev->regs->DR = (addr << 1) | rw; +} + #define I2C_IRQ_ERROR I2C_CR2_ITERREN #define I2C_IRQ_EVENT I2C_CR2_ITEVTEN #define I2C_IRQ_BUFFER I2C_CR2_ITBUFEN -void i2c_enable_irq(i2c_reg_map *regs, uint32 irqs); -void i2c_disable_irq(i2c_reg_map *regs, uint32 irqs); -void i2c_peripheral_enable(i2c_reg_map *regs); -void i2c_peripheral_disable(i2c_reg_map *regs); +static inline void i2c_enable_irq(i2c_dev *dev, uint32 irqs) { + dev->regs->CR2 |= irqs; +} + +static inline void i2c_disable_irq(i2c_dev *dev, uint32 irqs) { + dev->regs->CR2 &= ~irqs; +} + +static inline void i2c_enable_ack(i2c_dev *dev) { + dev->regs->CR1 |= I2C_CR1_ACK; +} -static inline void i2c_write(i2c_reg_map *regs, uint8 byte) { - regs->DR = byte; +static inline void i2c_disable_ack(i2c_dev *dev) { + dev->regs->CR1 &= ~I2C_CR1_ACK; } #ifdef __cplusplus diff --git a/libmaple/libmaple.h b/libmaple/libmaple.h index 6b75c96..50887bc 100644 --- a/libmaple/libmaple.h +++ b/libmaple/libmaple.h @@ -31,7 +31,9 @@ #define _LIBMAPLE_H_ #include "libmaple_types.h" +#include "stm32.h" #include "util.h" +#include "delay.h" /* * Where to put usercode, based on space reserved for bootloader. diff --git a/libmaple/rcc.c b/libmaple/rcc.c index d3fb6a3..6445958 100644 --- a/libmaple/rcc.c +++ b/libmaple/rcc.c @@ -75,7 +75,7 @@ static const struct rcc_dev_info rcc_dev_table[] = { [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 }, [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, // High-density only [RCC_PWR] = { .clk_domain = APB1, .line_num = 28}, - [RCC_BKP] = { .clk_domain = APB1, .line_num = 27} + [RCC_BKP] = { .clk_domain = APB1, .line_num = 27}, [RCC_I2C1] = { .clk_domain = APB1, .line_num = 21 }, // High-density only [RCC_I2C2] = { .clk_domain = APB1, .line_num = 22 }, // High-density only }; diff --git a/libmaple/stm32.h b/libmaple/stm32.h index e65b28c..21c18df 100644 --- a/libmaple/stm32.h +++ b/libmaple/stm32.h @@ -8,5 +8,15 @@ #define PCLK1 36000000U #define PCLK2 72000000U +#ifdef STM32_MEDIUM_DENSITY + #define NR_INTERRUPTS 43 +#else +#ifdef STM32_HIGH_DENSITY + #define NR_INTERRUPTS 60 +#else +#error "No STM32 board type defined!" +#endif +#endif + #endif diff --git a/main.cpp b/main.cpp index 5e3ddf3..7771fa7 100644 --- a/main.cpp +++ b/main.cpp @@ -6,19 +6,29 @@ static const uint8 slave_address = 0b1010001; -#define NR_ELEMENTS 64 +#define NR_ELEMENTS 4 uint8 buf0[NR_ELEMENTS + 2] = {0x0, 0x0}; uint8 buf1[] = {0x0, 0x0}; uint8 buf2[NR_ELEMENTS]; +i2c_msg msgs[3]; + +void toggle(void) { + digitalWrite(2, HIGH); + digitalWrite(2, LOW); +} + void setup() { - i2c_msg msgs[3]; uint32 i; pinMode(BOARD_LED_PIN, OUTPUT); + pinMode(2, OUTPUT); + Serial2.begin(9600); + Serial2.println("Hello!"); + digitalWrite(2, LOW); - for (i = 0; i < sizeof buf0; i++) { - buf0[i + 2] = i & 0xFF; + for (i = 2; i < sizeof buf0; i++) { + buf0[i] = i - 2; } i2c_master_enable(I2C1, 0); @@ -31,6 +41,11 @@ void setup() { i2c_master_xfer(I2C1, msgs, 1); delay(5); +} + +void loop() { + delay(100); + toggleLED(); /* Write slave address to read */ msgs[1].addr = slave_address; msgs[1].flags = 0; @@ -45,11 +60,6 @@ void setup() { i2c_master_xfer(I2C1, msgs + 1, 2); } -void loop() { - toggleLED(); - delay(100); -} - // Force init to be called *first*, i.e. before static object allocation. // Otherwise, statically allocated object that need libmaple may fail. __attribute__(( constructor )) void premain() { diff --git a/wirish/time.c b/wirish/time.c index c0a0649..b5663b0 100644 --- a/wirish/time.c +++ b/wirish/time.c @@ -29,6 +29,7 @@ #include "libmaple.h" #include "systick.h" #include "time.h" +#include "delay.h" void delay(unsigned long ms) { uint32 i; @@ -38,15 +39,5 @@ void delay(unsigned long ms) { } void delayMicroseconds(uint32 us) { - /* So (2^32)/12 micros max, or less than 6 minutes */ - us *= 12; - - /* fudge for function call overhead */ - us--; - asm volatile(" mov r0, %[us] \n\t" - "1: subs r0, #1 \n\t" - " bhi 1b \n\t" - : - : [us] "r" (us) - : "r0"); + delay_us(us); } -- cgit v1.2.3 From c8da1c3b7b6eb450138a00af9bbbee607f596837 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 7 Mar 2011 13:11:54 -0500 Subject: [WIP] GPIO refactor: seems ok, ready for review --- Makefile | 8 +- docs/Doxyfile | 6 +- examples/test-session.cpp | 28 +-- libmaple/adc.c | 4 +- libmaple/adc.h | 38 ++-- libmaple/bitband.h | 83 +++++++++ libmaple/bkp.c | 6 +- libmaple/bkp.h | 16 +- libmaple/dac.c | 6 +- libmaple/dac.h | 10 +- libmaple/exti.c | 244 +++++++++++++++---------- libmaple/exti.h | 158 ++++------------ libmaple/fsmc.c | 89 ++++----- libmaple/fsmc.h | 5 +- libmaple/gpio.c | 165 ++++++++++++++--- libmaple/gpio.h | 391 ++++++++++++++++++++++++++++++---------- libmaple/libmaple.h | 2 +- libmaple/libmaple_types.h | 1 + libmaple/pwr.h | 9 +- libmaple/rcc.h | 3 +- libmaple/ring_buffer.h | 17 +- libmaple/spi.c | 18 +- libmaple/usb/usb.c | 33 +++- libmaple/usb/usb_callbacks.c | 2 +- libmaple/usb/usb_config.h | 7 +- libmaple/usb/usb_hardware.c | 41 ----- libmaple/usb/usb_hardware.h | 36 +--- libmaple/util.c | 6 +- libmaple/util.h | 35 ++-- notes/coding_standard.txt | 85 +++++---- notes/exti.txt | 67 +++++++ wirish/HardwareTimer.cpp | 11 +- wirish/boards.cpp | 387 +++++++++++++++++++++++++++++++++++++++ wirish/boards.h | 401 ++--------------------------------------- wirish/comm/HardwareSerial.cpp | 14 +- wirish/comm/HardwareSerial.h | 4 +- wirish/ext_interrupts.c | 79 -------- wirish/ext_interrupts.cpp | 82 +++++++++ wirish/ext_interrupts.h | 11 +- wirish/io.h | 11 +- wirish/pwm.c | 48 ----- wirish/pwm.cpp | 48 +++++ wirish/pwm.h | 13 +- wirish/rules.mk | 32 ++-- wirish/time.c | 52 ------ wirish/time.cpp | 52 ++++++ wirish/time.h | 9 - wirish/wirish.c | 81 --------- wirish/wirish.cpp | 82 +++++++++ wirish/wirish.h | 16 +- wirish/wirish_analog.c | 41 ----- wirish/wirish_analog.cpp | 41 +++++ wirish/wirish_digital.c | 142 --------------- wirish/wirish_digital.cpp | 143 +++++++++++++++ wirish/wirish_math.h | 9 +- wirish/wirish_shift.c | 40 ---- wirish/wirish_shift.cpp | 40 ++++ 57 files changed, 1928 insertions(+), 1580 deletions(-) create mode 100644 libmaple/bitband.h create mode 100644 notes/exti.txt create mode 100644 wirish/boards.cpp delete mode 100644 wirish/ext_interrupts.c create mode 100644 wirish/ext_interrupts.cpp delete mode 100644 wirish/pwm.c create mode 100644 wirish/pwm.cpp delete mode 100644 wirish/time.c create mode 100644 wirish/time.cpp delete mode 100644 wirish/wirish.c create mode 100644 wirish/wirish.cpp delete mode 100644 wirish/wirish_analog.c create mode 100644 wirish/wirish_analog.cpp delete mode 100644 wirish/wirish_digital.c create mode 100644 wirish/wirish_digital.cpp delete mode 100644 wirish/wirish_shift.c create mode 100644 wirish/wirish_shift.cpp (limited to 'wirish') diff --git a/Makefile b/Makefile index 01e1e72..3804421 100644 --- a/Makefile +++ b/Makefile @@ -13,21 +13,21 @@ PRODUCT_ID := 0003 ifeq ($(BOARD), maple) MCU := STM32F103RB PRODUCT_ID := 0003 - ERROR_LED_PORT := GPIOA_BASE + ERROR_LED_PORT := GPIOA ERROR_LED_PIN := 5 DENSITY := STM32_MEDIUM_DENSITY endif ifeq ($(BOARD), maple_native) MCU := STM32F103ZE PRODUCT_ID := 0003 - ERROR_LED_PORT := GPIOC_BASE + ERROR_LED_PORT := GPIOC ERROR_LED_PIN := 15 DENSITY := STM32_HIGH_DENSITY endif ifeq ($(BOARD), maple_mini) MCU := STM32F103CB PRODUCT_ID := 0003 - ERROR_LED_PORT := GPIOB_BASE + ERROR_LED_PORT := GPIOB ERROR_LED_PIN := 1 DENSITY := STM32_MEDIUM_DENSITY endif @@ -45,7 +45,7 @@ SUPPORT_PATH := $(SRCROOT)/support # Compilation flags. # FIXME remove the ERROR_LED config GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m \ - -nostdlib \ + -nostdlib \ -ffunction-sections -fdata-sections -Wl,--gc-sections \ -DBOARD_$(BOARD) -DMCU_$(MCU) \ -DERROR_LED_PORT=$(ERROR_LED_PORT) \ diff --git a/docs/Doxyfile b/docs/Doxyfile index 3290843..9bf02fc 100644 --- a/docs/Doxyfile +++ b/docs/Doxyfile @@ -620,7 +620,9 @@ RECURSIVE = YES # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. -EXCLUDE = +# FIXME The USB thing needs to get redone (ST code stripped out, +# etc.). Until then, just ignore it. +EXCLUDE = ../libmaple/usb/ # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded @@ -1369,7 +1371,7 @@ INCLUDE_FILE_PATTERNS = # undefined via #undef or recursively expanded use the := operator # instead of the = operator. -PREDEFINED = ALWAYS_INLINE= \ +PREDEFINED = __attribute__()= \ __cplusplus # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 72d64d6..ea631ca 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -351,22 +351,22 @@ void cmd_everything(void) { // TODO } void fast_gpio(int maple_pin) { - GPIO_Port *port = PIN_MAP[maple_pin].port; + gpio_dev *dev = PIN_MAP[maple_pin].gpio_device; uint32 pin = PIN_MAP[maple_pin].pin; - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); - gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); } void cmd_serial1_serial3(void) { diff --git a/libmaple/adc.c b/libmaple/adc.c index a464746..9626a40 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -126,8 +126,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { * @param dev adc device */ static void adc_calibrate(const adc_dev *dev) { - __io uint32 *rstcal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 3); - __io uint32 *cal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 2); + __io uint32 *rstcal_bit = bb_peripv(&(dev->regs->CR2), 3); + __io uint32 *cal_bit = bb_peripv(&(dev->regs->CR2), 2); *rstcal_bit = 1; while (*rstcal_bit) diff --git a/libmaple/adc.h b/libmaple/adc.h index ac386fb..4811dbc 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -30,14 +30,16 @@ #ifndef _ADC_H_ #define _ADC_H_ -#include "util.h" +#include "libmaple.h" +#include "bitband.h" #include "rcc.h" #ifdef __cplusplus extern "C"{ #endif +/** ADC register map type. */ typedef struct adc_reg_map { __io uint32 SR; ///< Status register __io uint32 CR1; ///< Control register 1 @@ -61,22 +63,30 @@ typedef struct adc_reg_map { __io uint32 DR; ///< Regular data register } adc_reg_map; +/** ADC device type. */ typedef struct adc_dev { - adc_reg_map *regs; - rcc_clk_id clk_id; + adc_reg_map *regs; /**< Register map */ + rcc_clk_id clk_id; /**< RCC clock information */ } adc_dev; +/** ADC1 device. */ extern const adc_dev *ADC1; +/** ADC2 device. */ extern const adc_dev *ADC2; #ifdef STM32_HIGH_DENSITY +/** ADC3 device. */ extern const adc_dev *ADC3; #endif /* * ADC peripheral base addresses */ + +/** ADC1 register map base pointer. */ #define ADC1_BASE ((adc_reg_map*)0x40012400) +/** ADC2 register map base pointer. */ #define ADC2_BASE ((adc_reg_map*)0x40012800) +/** ADC3 register map base pointer. */ #define ADC3_BASE ((adc_reg_map*)0x40013C00) /* @@ -138,8 +148,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); /** * @brief Perform a single synchronous software triggered conversion on a - * channel - * @param regs ADC register map + * channel. + * @param dev ADC device to use for reading. * @param channel channel to convert * @return conversion result */ @@ -161,27 +171,27 @@ static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { /** * @brief Set external trigger conversion mode event for regular channels - * @param dev adc device - * @param enable if 1, conversion on external events is enabled, 0 to disable + * @param dev ADC device + * @param enable If 1, conversion on external events is enabled, 0 to disable */ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { - __write(BITBAND_PERI(&(dev->regs->CR2), 20), enable); + *bb_peripv(&dev->regs->CR2, 20) = !!enable; } /** * @brief Enable an adc peripheral - * @param regs register map of peripheral to enable + * @param dev ADC device to enable */ static inline void adc_enable(const adc_dev *dev) { - __write(BITBAND_PERI(&(dev->regs->CR2), 0), 1); + *bb_peripv(&dev->regs->CR2, 0) = 1; } /** - * @brief Disable an adc peripheral - * @param regs register map of peripheral to disable + * @brief Disable an ADC peripheral + * @param dev ADC device to disable */ static inline void adc_disable(const adc_dev *dev) { - __write(BITBAND_PERI(&(dev->regs->CR2), 0), 0); + *bb_peripv(&dev->regs->CR2, 0) = 0; } /** @@ -198,5 +208,5 @@ static inline void adc_disable_all(void) { #ifdef __cplusplus } // extern "C" #endif -#endif +#endif diff --git a/libmaple/bitband.h b/libmaple/bitband.h new file mode 100644 index 0000000..076335f --- /dev/null +++ b/libmaple/bitband.h @@ -0,0 +1,83 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file bitband.h + * + * @brief Bit-banding utility functions + */ + +#define BB_SRAM_REF 0x20000000 +#define BB_SRAM_BASE 0x22000000 +#define BB_PERI_REF 0x40000000 +#define BB_PERI_BASE 0x42000000 + +static inline uint32* __bb_addr(void*, uint32, uint32, uint32); +static inline __io uint32* __bb_addrv(__io void*, uint32, uint32, uint32); + +/** + * @brief Obtain a pointer to the bit-band address corresponding to a + * bit in an SRAM address. + * @param address Address in the bit-banded SRAM region + * @param bit Bit in address to bit-band + */ +static inline uint32* bb_sramp(void *address, uint32 bit) { + return __bb_addr(address, bit, BB_SRAM_BASE, BB_SRAM_REF); +} + +/** + * @brief Obtain a pointer to the bit-band address corresponding to a + * bit in a volatile SRAM address. + * @param address Address in the bit-banded SRAM region + * @param bit Bit in address to bit-band + */ +static inline __io uint32* bb_srampv(__io void *address, uint32 bit) { + return __bb_addrv(address, bit, BB_SRAM_BASE, BB_SRAM_REF); +} + +/** + * @brief Obtain a pointer to the bit-band address corresponding to a + * bit in a peripheral address. + * @param address Address in the bit-banded peripheral region + * @param bit Bit in address to bit-band + */ +static inline __io uint32* bb_peripv(__io void *address, uint32 bit) { + return __bb_addrv(address, bit, BB_PERI_BASE, BB_PERI_REF); +} + +static inline uint32* __bb_addr(void *address, + uint32 bit, + uint32 bb_base, + uint32 bb_ref) { + return (uint32*)(bb_base + ((uint32)address - bb_ref) * 32 + bit * 4); +} + +static inline __io uint32* __bb_addrv(__io void *address, + uint32 bit, + uint32 bb_base, + uint32 bb_ref) { + return (__io uint32*)__bb_addr((void*)address, bit, bb_base, bb_ref); +} diff --git a/libmaple/bkp.c b/libmaple/bkp.c index ed107d8..b152069 100644 --- a/libmaple/bkp.c +++ b/libmaple/bkp.c @@ -27,7 +27,7 @@ #include "bkp.h" #include "pwr.h" #include "rcc.h" -#include "util.h" +#include "bitband.h" static inline __io uint32* data_register(uint8 reg); @@ -57,14 +57,14 @@ void bkp_init(void) { * @see bkp_init() */ void bkp_enable_writes(void) { - __write(BITBAND_PERI(&(PWR_BASE->CR), PWR_CR_DBP), 1); + *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 1; } /** * Disable write access to the backup registers. */ void bkp_disable_writes(void) { - __write(BITBAND_PERI(&(PWR_BASE->CR), PWR_CR_DBP), 0); + *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 0; } /** diff --git a/libmaple/bkp.h b/libmaple/bkp.h index 96ef8d2..cea39b6 100644 --- a/libmaple/bkp.h +++ b/libmaple/bkp.h @@ -44,6 +44,7 @@ extern "C" { #define BKP_NR_DATA_REGS 42 #endif +/** Backup peripheral register map type. */ typedef struct bkp_reg_map { const uint32 RESERVED1; __io uint32 DR1; ///< Data register 1 @@ -97,20 +98,17 @@ typedef struct bkp_reg_map { #endif } bkp_reg_map; +/** Backup peripheral register map base pointer. */ +#define BKP_BASE ((bkp_reg_map*)0x40006C00) + +/** Backup peripheral device type. */ typedef struct bkp_dev { - bkp_reg_map *regs; + bkp_reg_map *regs; /**< Register map */ } bkp_dev; -/** - * Backup device. - */ +/** Backup device. */ extern const bkp_dev *BKP; -/* - * Backup peripheral base. - */ -#define BKP_BASE ((bkp_reg_map*)0x40006C00) - void bkp_init(void); void bkp_enable_writes(void); void bkp_disable_writes(void); diff --git a/libmaple/dac.c b/libmaple/dac.c index 54b555b..ef3a9f9 100644 --- a/libmaple/dac.c +++ b/libmaple/dac.c @@ -80,15 +80,15 @@ void dac_write_channel(uint8 channel, uint16 val) { void dac_enable_channel(uint8 channel) { /* * Setup ANALOG mode on PA4 and PA5. This mapping is consistent across - * all STM32 chips with a DAC. See RM008 12.2. + * all STM32 chips with a DAC. See RM0008 12.2. */ switch (channel) { case 1: - gpio_set_mode(GPIOA_BASE, 4, GPIO_MODE_INPUT_ANALOG); + gpio_set_mode(GPIOA, 4, GPIO_INPUT_ANALOG); DAC->regs->CR |= DAC_CR_EN1; break; case 2: - gpio_set_mode(GPIOA_BASE, 5, GPIO_MODE_INPUT_ANALOG); + gpio_set_mode(GPIOA, 5, GPIO_INPUT_ANALOG); DAC->regs->CR |= DAC_CR_EN2; break; } diff --git a/libmaple/dac.h b/libmaple/dac.h index bc64324..c897bb2 100644 --- a/libmaple/dac.h +++ b/libmaple/dac.h @@ -25,9 +25,10 @@ /** * @file dac.h * @brief Digital to analog converter header file - * See notes/dac.txt for more info */ +/* See notes/dac.txt for more info */ + #ifndef _DAC_H_ #define _DAC_H_ @@ -63,16 +64,15 @@ typedef struct dac_reg_map { __io uint32 DOR2; /**< Channel 2 data output register */ } dac_reg_map; +/** DAC device type. */ typedef struct dac_dev { - dac_reg_map *regs; + dac_reg_map *regs; /**< Register map */ } dac_dev; /** DAC device. */ extern const dac_dev *DAC; -/* - * DAC peripheral base address - */ +/** DAC register map base address */ #define DAC_BASE ((dac_reg_map*)0x40007400) /* diff --git a/libmaple/exti.c b/libmaple/exti.c index e8ad52a..8177e1e 100644 --- a/libmaple/exti.c +++ b/libmaple/exti.c @@ -23,19 +23,29 @@ *****************************************************************************/ /** + * @file exti.c * @brief External interrupt control routines */ #include "libmaple.h" #include "exti.h" #include "nvic.h" +#include "bitband.h" -typedef struct ExtIChannel { +/* + * Internal state + */ + +/* Status bitmaps, for external interrupts with multiplexed IRQs */ +static uint16 exti_9_5_en = 0; +static uint16 exti_15_10_en = 0; + +typedef struct exti_channel { void (*handler)(void); uint32 irq_line; -} ExtIChannel; +} exti_channel; -static ExtIChannel exti_channels[] = { +static exti_channel exti_channels[] = { { .handler = NULL, .irq_line = NVIC_EXTI0 }, // EXTI0 { .handler = NULL, .irq_line = NVIC_EXTI1 }, // EXTI1 { .handler = NULL, .irq_line = NVIC_EXTI2 }, // EXTI2 @@ -54,63 +64,127 @@ static ExtIChannel exti_channels[] = { { .handler = NULL, .irq_line = NVIC_EXTI15_10 }, // EXTI15 }; -static inline void clear_pending(int bit) { - __set_bits(EXTI_PR, BIT(bit)); - /* If the pending bit is cleared as the last instruction in an ISR, - * it won't actually be cleared in time and the ISR will fire again. - * Insert a 2-cycle buffer to allow it to take effect. */ - asm volatile("nop"); - asm volatile("nop"); -} +/* + * Convenience routines + */ + +static inline void enable_irq(afio_exti_num exti_num); +static inline void maybe_disable_irq(afio_exti_num exti_num); + +/** + * @brief Register a handler to run upon external interrupt. + * + * This function assumes that the interrupt request corresponding to + * the given external interrupt is masked. + * + * @param num External interrupt line number. + * @param port Port to use as source input for external interrupt. + * @param handler Function handler to execute when interrupt is triggered. + * @param mode Type of transition to trigger on, one of: + * EXTI_RISING, EXTI_FALLING, EXTI_RISING_FALLING. + * @see exti_num + * @see exti_port + * @see exti_trigger_mode + */ +void exti_attach_interrupt(afio_exti_num num, + afio_exti_port port, + voidFuncPtr handler, + exti_trigger_mode mode) { + ASSERT(handler); -static inline void dispatch_handler(uint32 channel) { - ASSERT(exti_channels[channel].handler); - if (exti_channels[channel].handler) { - (exti_channels[channel].handler)(); + /* Register the handler */ + exti_channels[num].handler = handler; + + /* Set trigger mode */ + switch (mode) { + case EXTI_RISING: + *bb_peripv(&EXTI_BASE->RTSR, num) = 1; + break; + case EXTI_FALLING: + *bb_peripv(&EXTI_BASE->FTSR, num) = 1; + break; + case EXTI_RISING_FALLING: + *bb_peripv(&EXTI_BASE->RTSR, num) = 1; + *bb_peripv(&EXTI_BASE->FTSR, num) = 1; + break; } + + /* Map num to port */ + afio_exti_select(num, port); + + /* Unmask external interrupt request */ + *bb_peripv(&EXTI_BASE->IMR, num) = 1; + + /* Enable the interrupt line */ + enable_irq(num); +} + +/** + * @brief Unregister an external interrupt handler + * @param num Number of the external interrupt line to disable. + * @see exti_num + */ +void exti_detach_interrupt(afio_exti_num num) { + /* First, mask the interrupt request */ + *bb_peripv(&EXTI_BASE->IMR, num) = 0; + + /* Then, clear the trigger selection registers */ + *bb_peripv(&EXTI_BASE->FTSR, num) = 0; + *bb_peripv(&EXTI_BASE->RTSR, num) = 0; + + /* Next, disable the IRQ, unless it's multiplexed and there are + * other active external interrupts on the same IRQ line */ + maybe_disable_irq(num); + + /* Finally, unregister the user's handler */ + exti_channels[num].handler = NULL; } -/* For EXTI0 through EXTI4, only one handler - * is associated with each channel, so we - * don't have to keep track of which channel +/* + * Interrupt handlers + */ + +static inline void clear_pending(uint32 exti_num); +static inline void dispatch_handler(uint32 exti_num); + +/* For AFIO_EXTI_0 through AFIO_EXTI_4, only one handler is associated + * with each channel, so we don't have to keep track of which channel * we came from */ void __irq_exti0(void) { - dispatch_handler(EXTI0); - clear_pending(EXTI0); + dispatch_handler(AFIO_EXTI_0); + clear_pending(AFIO_EXTI_0); } void __irq_exti1(void) { - dispatch_handler(EXTI1); - clear_pending(EXTI1); + dispatch_handler(AFIO_EXTI_1); + clear_pending(AFIO_EXTI_1); } void __irq_exti2(void) { - dispatch_handler(EXTI2); - clear_pending(EXTI2); + dispatch_handler(AFIO_EXTI_2); + clear_pending(AFIO_EXTI_2); } void __irq_exti3(void) { - dispatch_handler(EXTI3); - clear_pending(EXTI3); + dispatch_handler(AFIO_EXTI_3); + clear_pending(AFIO_EXTI_3); } void __irq_exti4(void) { - dispatch_handler(EXTI4); - clear_pending(EXTI4); + dispatch_handler(AFIO_EXTI_4); + clear_pending(AFIO_EXTI_4); } void __irq_exti9_5(void) { /* Figure out which channel it came from */ - uint32 pending; + uint32 pending = GET_BITS(EXTI_BASE->PR, 5, 9); uint32 i; - pending = REG_GET(EXTI_PR); - pending = GET_BITS(pending, 5, 9); /* Dispatch every handler if the pending bit is set */ for (i = 0; i < 5; i++) { if (pending & 0x1) { - dispatch_handler(EXTI5 + i); - clear_pending(EXTI5 + i); + dispatch_handler(AFIO_EXTI_5 + i); + clear_pending(AFIO_EXTI_5 + i); } pending >>= 1; } @@ -118,89 +192,59 @@ void __irq_exti9_5(void) { void __irq_exti15_10(void) { /* Figure out which channel it came from */ - uint32 pending; + uint32 pending = GET_BITS(EXTI_BASE->PR, 10, 15); uint32 i; - pending = REG_GET(EXTI_PR); - pending = GET_BITS(pending, 10, 15); /* Dispatch every handler if the pending bit is set */ for (i = 0; i < 6; i++) { if (pending & 0x1) { - dispatch_handler(EXTI10 + i); - clear_pending(EXTI10 + i); + dispatch_handler(AFIO_EXTI_10 + i); + clear_pending(AFIO_EXTI_10 + i); } pending >>= 1; } } - -/** - * @brief Register a handler to run upon external interrupt - * @param port source port of pin (eg EXTI_CONFIG_PORTA) - * @param pin pin number on the source port - * @param handler function handler to execute - * @param mode type of transition to trigger on +/* + * Auxiliary functions */ -void exti_attach_interrupt(uint32 port, - uint32 pin, - voidFuncPtr handler, - uint32 mode) { - static uint32 afio_regs[] = { - AFIO_EXTICR1, // EXT0-3 - AFIO_EXTICR2, // EXT4-7 - AFIO_EXTICR3, // EXT8-11 - AFIO_EXTICR4, // EXT12-15 - }; - - /* Note: All of the following code assumes that EXTI0 = 0 */ - ASSERT(EXTI0 == 0); - ASSERT(handler); - - uint32 channel = pin; - /* map port to channel */ - __write(afio_regs[pin/4], (port << ((pin % 4) * 4))); - - /* Unmask appropriate interrupt line */ - __set_bits(EXTI_IMR, BIT(channel)); - - /* Set trigger mode */ - switch (mode) { - case EXTI_RISING: - __set_bits(EXTI_RTSR, BIT(channel)); - break; - - case EXTI_FALLING: - __set_bits(EXTI_FTSR, BIT(channel)); - break; +static inline void clear_pending(uint32 exti_num) { + *bb_peripv(&EXTI_BASE->PR, exti_num) = 1; + /* If the pending bit is cleared as the last instruction in an ISR, + * it won't actually be cleared in time and the ISR will fire again. + * Insert a 2-cycle buffer to allow it to take effect. */ + asm volatile("nop"); + asm volatile("nop"); +} - case EXTI_RISING_FALLING: - __set_bits(EXTI_RTSR, BIT(channel)); - __set_bits(EXTI_FTSR, BIT(channel)); - break; +static inline void dispatch_handler(uint32 exti_num) { + ASSERT(exti_channels[exti_num].handler); + if (exti_channels[exti_num].handler) { + (exti_channels[exti_num].handler)(); } - - /* Register the handler */ - exti_channels[channel].handler = handler; - - /* Configure the enable interrupt bits for the NVIC */ - nvic_irq_enable(exti_channels[channel].irq_line); } +static inline void enable_irq(afio_exti_num exti) { + /* Maybe twiddle the IRQ bitmap for extis with multiplexed IRQs */ + if (exti > 4) { + uint16 *bitmap = exti < 10 ? &exti_9_5_en : &exti_15_10_en; + *bb_sramp(bitmap, exti) = 1; + } -/** - * @brief Unregister an external interrupt handler - * @param channel channel to disable (eg EXTI0) - */ -void exti_detach_interrupt(uint32 channel) { - ASSERT(channel < NR_EXTI_CHANNELS); - ASSERT(EXTI0 == 0); - - __clear_bits(EXTI_IMR, BIT(channel)); - __clear_bits(EXTI_FTSR, BIT(channel)); - __clear_bits(EXTI_RTSR, BIT(channel)); - - nvic_irq_disable(exti_channels[channel].irq_line); + nvic_irq_enable(exti_channels[exti].irq_line); +} - exti_channels[channel].handler = NULL; +static inline void maybe_disable_irq(afio_exti_num exti) { + if (exti > 4) { + uint16 *bitmap = exti < 10 ? &exti_9_5_en : &exti_15_10_en; + *bb_sramp(bitmap, exti) = 0; + if (*bitmap == 0) { + /* All of the external interrupts which share this IRQ + * line are disabled. */ + nvic_irq_disable(exti_channels[exti].irq_line); + } + } else { + nvic_irq_disable(exti_channels[exti].irq_line); + } } diff --git a/libmaple/exti.h b/libmaple/exti.h index 806578f..e145033 100644 --- a/libmaple/exti.h +++ b/libmaple/exti.h @@ -22,145 +22,51 @@ * THE SOFTWARE. *****************************************************************************/ - /** - * @file exti.h - * - * @brief External interrupt control prototypes and defines + * @file exti.h + * @brief External interrupt control prototypes and defines */ -#ifndef _EXTI_H_ -#define _EXTI_H_ - -/* Notes: - * - * To generate the interrupt, the interrupt line should be configured - * and enabled. This is done by programming the two trigger registers - * with the desired edge detection and by enabling the interrupt - * request by writing a '1' to the corresponding bit in the interrupt - * mask register. When the selected edge occurs on the external - * interrupt line, an interrupt request is generated. The pending bit - * corresponding to the interrupt line is also set. This request is - * reset by writing a '1' in the pending register. - * - * Hardware interrupt selection: - * - * To configure the 20 lines as interrupt sources, use the following - * procedure: - * - * 1) Configure AFIO_EXTIICR[y] to select the source input for EXTIx - * external interrupt - * 2) Configure the mask bits of the 20 interrupt lines (EXTI_IMR) - * 3) Configure the trigger selection bits of the interrupt lines - * (EXTI_RTSR and EXTI_FTSR) - * 4) Configure the enable and mask bits that control the NVIC_IRQ - * channel mapped to the External - * - * Interrupt Controller (EXTI) so that an inerrupt coming from one of - * the 20 lines can be correctly acknowledged. - * - * AFIO clock must be on. - * - * RM0008, page 107: "PD0, PD1 cannot be used for external - * interrupt/event generation on 36, 48, 64-bin packages." - * - * ---------------------------------------------------------------------------- - * Pin to EXTI Line Mappings: - * EXTI0 EXTI1 EXTI2 EXTI3 EXTI4 - * -------------------------------------------------------------------------- - * D2/PA0 D3/PA1 D1/PA2 D0/A6/PA3 D10/A10/PA4 - * D26/EXT7/PB0 D27/EXT8/PB1 D16/A2/PC2 D17/A3/PC3 D18/A4/PC4 - * D14/A0/PC0 D15/PC1 D25/EXT5/PD2 - * - * EXTI5 EXTI6 EXTI7 EXTI8 EXTI9 - * ---------------------------------------------------------------------------- - * D13/A13/PA5 D12/A12/PA6 D11/A11/PA7 D6/PA8 D7/PA9 - * D4/PB5 D5/PB6 D9/PB7 D38/PB8 D23/EXT4/PB9 - * D19/A5/PC5 D34/EXTI15/PC6 D35/EXT16/PC7 D36/PC8 D37/EXT18/PC9 - * - * EXTI10 EXTI11 EXTI12 EXTI13 EXTI14 - * ---------------------------------------------------------------------------- - * D8/PA10 D29/EXT10/PB11 D30/EXTI1/PB12 D31/EXTI12/PB13 D32/EXT13/PB14 - * D28/PB10 D20/EXTI1/PC13 D21/EXT2/PC14 - * D25/PC10 - * - * EXTI15 - * ---------------------------------------------------------------------------- - * D33/EXTI14/PB15 - * D22/EXT3/PC15 - * - * - * The 16 EXTI interrupts are mapped to 7 interrupt handlers. - * - * EXTI Lines to Interrupt Mapping: - * EXTI0 -> EXTI0 - * EXTI1 -> EXTI1 - * EXTI2 -> EXTI2 - * EXTI3 -> EXTI3 - * EXTI4 -> EXTI4 - * EXTI[5-9] -> EXT9_5 - * EXTI[10-15] -> EXT15_10 - * - * */ - -#define NR_EXTI_MODES 3 -#define NR_EXTI_CHANNELS 16 -#define NR_EXTI_PORTS NR_GPIO_PORTS // board specific +/* See notes/exti.txt for more info */ -#define EXTI_RISING 0 -#define EXTI_FALLING 1 -#define EXTI_RISING_FALLING 2 +#include "libmaple.h" +#include "gpio.h" -#define EXTI_IMR 0x40010400 // Interrupt mask register -#define EXTI_EMR (EXTI_IMR + 0x04) // Event mask register -#define EXTI_RTSR (EXTI_IMR + 0x08) // Rising trigger selection register -#define EXTI_FTSR (EXTI_IMR + 0x0C) // Falling trigger selection register -#define EXTI_SWIER (EXTI_IMR + 0x10) // Software interrupt event register -#define EXTI_PR (EXTI_IMR + 0x14) // Pending register - -#define AFIO_EVCR 0x40010000 -#define AFIO_EXTICR1 (AFIO_EVCR + 0x08) -#define AFIO_EXTICR2 (AFIO_EVCR + 0x0C) -#define AFIO_EXTICR3 (AFIO_EVCR + 0x10) -#define AFIO_EXTICR4 (AFIO_EVCR + 0x14) - -#define EXTI0 0 -#define EXTI1 1 -#define EXTI2 2 -#define EXTI3 3 -#define EXTI4 4 -#define EXTI5 5 -#define EXTI6 6 -#define EXTI7 7 -#define EXTI8 8 -#define EXTI9 9 -#define EXTI10 10 -#define EXTI11 11 -#define EXTI12 12 -#define EXTI13 13 -#define EXTI14 14 -#define EXTI15 15 - -#define EXTI_CONFIG_PORTA 0 // Maple, Maple Native, Maple Mini -#define EXTI_CONFIG_PORTB 1 // Maple, Maple Native, Maple Mini -#define EXTI_CONFIG_PORTC 2 // Maple, Maple Native, Maple Mini -#define EXTI_CONFIG_PORTD 3 // Maple and Maple Native only -#define EXTI_CONFIG_PORTE 4 // Native only -#define EXTI_CONFIG_PORTF 5 // Native only -#define EXTI_CONFIG_PORTG 6 // Native only +#ifndef _EXTI_H_ +#define _EXTI_H_ #ifdef __cplusplus extern "C"{ #endif -void exti_attach_interrupt(uint32 port, uint32 pin, voidFuncPtr handler, - uint32 mode); -void exti_detach_interrupt(uint32 channel); +/** EXTI register map type */ +typedef struct exti_reg_map { + __io uint32 IMR; /**< Interrupt mask register */ + __io uint32 EMR; /**< Event mask register */ + __io uint32 RTSR; /**< Rising trigger selection register */ + __io uint32 FTSR; /**< Falling trigger selection register */ + __io uint32 SWIER; /**< Software interrupt event register */ + __io uint32 PR; /**< Pending register */ +} exti_reg_map; + +/** EXTI register map base pointer */ +#define EXTI_BASE ((exti_reg_map*)0x40010400) + +/** External interrupt trigger mode */ +typedef enum exti_trigger_mode { + EXTI_RISING, /**< Trigger on the rising edge */ + EXTI_FALLING, /**< Trigger on the falling edge */ + EXTI_RISING_FALLING /**< Trigger on both the rising and falling edges */ +} exti_trigger_mode; + +void exti_attach_interrupt(afio_exti_num num, + afio_exti_port port, + voidFuncPtr handler, + exti_trigger_mode mode); +void exti_detach_interrupt(afio_exti_num num); #ifdef __cplusplus } // extern "C" #endif - #endif - diff --git a/libmaple/fsmc.c b/libmaple/fsmc.c index 49526f4..1561add 100644 --- a/libmaple/fsmc.c +++ b/libmaple/fsmc.c @@ -31,6 +31,8 @@ #include "gpio.h" #include "fsmc.h" +#ifdef STM32_HIGH_DENSITY + /* These values determined for a particular SRAM chip by following the * calculations in the ST FSMC application note. */ #define FSMC_ADDSET 0x0 @@ -45,55 +47,55 @@ void fsmc_native_sram_init(void) { /* First we setup all the GPIO pins. */ /* Data lines... */ - gpio_set_mode(GPIOD_BASE, 0, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 1, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 8, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 9, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 10, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 14, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 15, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 7, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 8, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 9, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 10, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 11, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 12, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 13, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 14, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOE_BASE, 15, MODE_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 8, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 9, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 10, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 15, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 7, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 8, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 9, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 10, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 11, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 12, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 13, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 14, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOE, 15, GPIO_AF_OUTPUT_PP); /* Address lines... */ - gpio_set_mode(GPIOD_BASE, 11, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 12, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOD_BASE, 13, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 0, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 1, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 2, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 3, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 4, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 5, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 12, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 13, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 14, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOF_BASE, 15, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 0, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 1, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 2, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 3, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 4, MODE_AF_OUTPUT_PP); - gpio_set_mode(GPIOG_BASE, 5, MODE_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 11, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 12, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOD, 13, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 0, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 1, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 2, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 3, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 4, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 5, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 12, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 13, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 14, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOF, 15, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 0, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 1, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 2, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 3, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 4, GPIO_AF_OUTPUT_PP); + gpio_set_mode(GPIOG, 5, GPIO_AF_OUTPUT_PP); /* And control lines... */ - gpio_set_mode(GPIOD_BASE, 4, MODE_AF_OUTPUT_PP); // NOE - gpio_set_mode(GPIOD_BASE, 5, MODE_AF_OUTPUT_PP); // NWE + gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // NOE + gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // NWE - gpio_set_mode(GPIOD_BASE, 7, MODE_AF_OUTPUT_PP); // NE1 - gpio_set_mode(GPIOG_BASE, 9, MODE_AF_OUTPUT_PP); // NE2 - gpio_set_mode(GPIOG_BASE, 10, MODE_AF_OUTPUT_PP); // NE3 - gpio_set_mode(GPIOG_BASE, 12, MODE_AF_OUTPUT_PP); // NE4 + gpio_set_mode(GPIOD, 7, GPIO_AF_OUTPUT_PP); // NE1 + gpio_set_mode(GPIOG, 9, GPIO_AF_OUTPUT_PP); // NE2 + gpio_set_mode(GPIOG, 10, GPIO_AF_OUTPUT_PP); // NE3 + gpio_set_mode(GPIOG, 12, GPIO_AF_OUTPUT_PP); // NE4 - gpio_set_mode(GPIOE_BASE, 0, MODE_AF_OUTPUT_PP); // NBL0 - gpio_set_mode(GPIOE_BASE, 1, MODE_AF_OUTPUT_PP); // NBL1 + gpio_set_mode(GPIOE, 0, GPIO_AF_OUTPUT_PP); // NBL0 + gpio_set_mode(GPIOE, 1, GPIO_AF_OUTPUT_PP); // NBL1 /* Next enable the clock */ rcc_clk_enable(RCC_FSMC); @@ -132,3 +134,4 @@ void fsmc_native_sram_init(void) { /* (FSMC_BWTR3 not used for this simple configuration.) */ } +#endif /* STM32_HIGH_DENSITY */ diff --git a/libmaple/fsmc.h b/libmaple/fsmc.h index e83b529..fed6894 100644 --- a/libmaple/fsmc.h +++ b/libmaple/fsmc.h @@ -37,6 +37,8 @@ extern "C"{ #endif +#ifdef STM32_HIGH_DENSITY + // There are 4 FSMC chip-select devices; here are the SRAM-specific registers // for each @@ -82,9 +84,10 @@ typedef struct { void fsmc_native_sram_init(void); +#endif /* STM32_HIGH_DENSITY */ + #ifdef __cplusplus } // extern "C" #endif - #endif diff --git a/libmaple/gpio.c b/libmaple/gpio.c index 71e5230..b08be12 100644 --- a/libmaple/gpio.c +++ b/libmaple/gpio.c @@ -26,44 +26,151 @@ * @brief GPIO initialization routine */ -#include "libmaple.h" -#include "rcc.h" #include "gpio.h" +#include "rcc.h" + +/* + * GPIO devices + */ + +static gpio_dev gpioa = { + .regs = GPIOA_BASE, + .clk_id = RCC_GPIOA +}; +/** GPIO port A device. */ +gpio_dev *GPIOA = &gpioa; + +static gpio_dev gpiob = { + .regs = GPIOB_BASE, + .clk_id = RCC_GPIOB +}; +/** GPIO port B device. */ +gpio_dev *GPIOB = &gpiob; + +static gpio_dev gpioc = { + .regs = GPIOC_BASE, + .clk_id = RCC_GPIOC +}; +/** GPIO port C device. */ +gpio_dev *GPIOC = &gpioc; + +static gpio_dev gpiod = { + .regs = GPIOD_BASE, + .clk_id = RCC_GPIOD +}; +/** GPIO port D device. */ +gpio_dev *GPIOD = &gpiod; + +#ifdef STM32_HIGH_ +static gpio_dev gpioe = { + .regs = GPIOE_BASE, + .clk_id = RCC_GPIOE +}; +/** GPIO port E device. */ +gpio_dev *GPIOE = &gpioe; + +static gpio_dev gpiof = { + .regs = GPIOF_BASE, + .clk_id = RCC_GPIOF +}; +/** GPIO port F device. */ +gpio_dev *GPIOF = &gpiof; -void gpio_init(void) { - rcc_clk_enable(RCC_GPIOA); - rcc_clk_enable(RCC_GPIOB); - rcc_clk_enable(RCC_GPIOC); -#if NR_GPIO_PORTS >= 4 /* Maple, but not Maple Mini */ - rcc_clk_enable(RCC_GPIOD); -#elif NR_GPIO_PORTS >= 7 /* Maple Native (high density only) */ - rcc_clk_enable(RCC_GPIOE); - rcc_clk_enable(RCC_GPIOF); - rcc_clk_enable(RCC_GPIOG); +static gpio_dev gpiog = { + .regs = GPIOG_BASE, + .clk_id = RCC_GPIOG +}; +/** GPIO port G device. */ +gpio_dev *GPIOG = &gpiog; #endif - rcc_clk_enable(RCC_AFIO); + +/* + * GPIO convenience routines + */ + +/** + * Initialize a GPIO device. + * + * Enables the clock for and resets the given device. + * + * @param dev GPIO device to initialize. + */ +void gpio_init(gpio_dev *dev) { + rcc_clk_enable(dev->clk_id); + rcc_reset_dev(dev->clk_id); } -void gpio_set_mode(GPIO_Port* port, uint8 gpio_pin, GPIOPinMode mode) { - uint32 tmp; - uint32 shift = POS(gpio_pin % 8); - GPIOReg CR; +/** + * Initialize and reset all available GPIO devices. + */ +void gpio_init_all(void) { + gpio_init(GPIOA); + gpio_init(GPIOB); + gpio_init(GPIOC); + gpio_init(GPIOD); +#ifdef STM32_HIGH_DENSITY + gpio_init(GPIOE); + gpio_init(GPIOF); + gpio_init(GPIOG); +#endif +} - ASSERT(port); - ASSERT(gpio_pin < 16); +/** + * Set the mode of a GPIO pin. + * + * @param dev GPIO device. + * @param pin Pin on the device whose mode to set, 0--15. + * @param mode General purpose or alternate function mode to set the pin to. + * @see gpio_pin_mode + */ +void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode) { + gpio_reg_map *regs = dev->regs; + __io uint32 *cr = ®s->CRL + (pin >> 3); + uint32 shift = (pin & 0x7) * 4; + uint32 tmp = *cr; + + tmp &= ~(0xF << shift); + tmp |= (mode == GPIO_INPUT_PU ? GPIO_INPUT_PD : mode) << shift; + *cr = tmp; - if (mode == GPIO_MODE_INPUT_PU) { - port->ODR |= BIT(gpio_pin); - mode = CNF_INPUT_PD; - } else if (mode == GPIO_MODE_INPUT_PD) { - port->ODR &= ~BIT(gpio_pin); + if (mode == GPIO_INPUT_PD) { + regs->ODR &= ~BIT(pin); + } else if (mode == GPIO_INPUT_PU) { + regs->ODR |= BIT(pin); } +} + +/* + * AFIO + */ - CR = (gpio_pin < 8) ? &(port->CRL) : &(port->CRH); +/** + * Initialize the AFIO clock, and reset the AFIO registers. + */ +void afio_init(void) { + rcc_clk_enable(RCC_AFIO); + rcc_reset_dev(RCC_AFIO); +} - tmp = *CR; - tmp &= POS_MASK(shift); - tmp |= mode << shift; +#define AFIO_EXTI_SEL_MASK 0xF + +/** + * Select a source input for an external interrupt. + * + * @param exti External interrupt. One of: AFIO_EXTI_0, + * AFIO_EXTI_1, ..., AFIO_EXTI_15. + * @param gpio_port Port which contains pin to use as source input. + * One of: AFIO_EXTI_PA, AFIO_EXTI_PB, AFIO_EXTI_PC, + * AFIO_EXTI_PD, and, on high density devices, + * AFIO_EXTI_PE, AFIO_EXTI_PF, AFIO_EXTI_PG. + * @see exti_port + */ +void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port) { + __io uint32 *exti_cr = &AFIO_BASE->EXTICR1 + exti / 4; + uint32 shift = 4 * (exti % 4); + uint32 cr = *exti_cr; - *CR = tmp; + cr &= ~(AFIO_EXTI_SEL_MASK << shift); + cr |= gpio_port << shift; + *exti_cr = cr; } diff --git a/libmaple/gpio.h b/libmaple/gpio.h index 53f77c4..48dbc00 100644 --- a/libmaple/gpio.h +++ b/libmaple/gpio.h @@ -3,126 +3,331 @@ * * Copyright (c) 2010 Perry Hung. * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. *****************************************************************************/ /** * @file gpio.h * - * @brief GPIO prototypes, defines, and inlined access functions + * @brief General purpose I/0 (GPIO) and Alternate Function I/O + * (AFIO) prototypes, defines, and inlined access functions. */ -#ifndef _GPIO_H -#define _GPIO_H - -/* Each of the GPIO port bits can be in the following modes (STM32 138/995): - * Input floating - * Input pull-up - * Input pull-down - * Analog Input - * Output open-drain - * Output push-pull - * Alternate function push-pull - * Alternate function open-drain - * - * - After reset, the alternate functions are not active and IO prts - * are set to Input Floating mode, EXCEPT for the Serial Wire and JTAG - * ports, which are in alternate function mode by default. */ - -#define AFIO_MAPR ((volatile uint32*)0x40010004) - -#define GPIOA_BASE ((GPIO_Port*)0x40010800) -#define GPIOB_BASE ((GPIO_Port*)0x40010C00) -#define GPIOC_BASE ((GPIO_Port*)0x40011000) -#define GPIOD_BASE ((GPIO_Port*)0x40011400) -#define GPIOE_BASE ((GPIO_Port*)0x40011800) // High-density devices only -#define GPIOF_BASE ((GPIO_Port*)0x40011C00) // High-density devices only -#define GPIOG_BASE ((GPIO_Port*)0x40012000) // High-density devices only - -#define GPIO_SPEED_50MHZ (0x3) - -#define MODE_OUTPUT_PP ((0x00 << 2) | GPIO_SPEED_50MHZ) -#define MODE_OUTPUT_OD ((0x01 << 2) | GPIO_SPEED_50MHZ) -#define MODE_AF_OUTPUT_PP ((0x02 << 2) | GPIO_SPEED_50MHZ) -#define MODE_AF_OUTPUT_OD ((0x03 << 2) | GPIO_SPEED_50MHZ) - -#define CNF_INPUT_ANALOG (0x00 << 2) -#define CNF_INPUT_FLOATING (0x01 << 2) -#define CNF_INPUT_PD (0x02 << 2) -#define CNF_INPUT_PU (0x02 << 2) - -typedef enum GPIOPinMode { - GPIO_MODE_OUTPUT_PP = MODE_OUTPUT_PP, - GPIO_MODE_OUTPUT_OD = MODE_OUTPUT_OD, - GPIO_MODE_AF_OUTPUT_PP = MODE_AF_OUTPUT_PP, - GPIO_MODE_AF_OUTPUT_OD = MODE_AF_OUTPUT_OD, - GPIO_MODE_INPUT_ANALOG = CNF_INPUT_ANALOG, - GPIO_MODE_INPUT_FLOATING = CNF_INPUT_FLOATING, - GPIO_MODE_INPUT_PD = CNF_INPUT_PD, - GPIO_MODE_INPUT_PU, -} GPIOPinMode; - -typedef struct { - volatile uint32 CRL; // Port configuration register low - volatile uint32 CRH; // Port configuration register high - volatile uint32 IDR; // Port input data register - volatile uint32 ODR; // Port output data register - volatile uint32 BSRR; // Port bit set/reset register - volatile uint32 BRR; // Port bit reset register - volatile uint32 LCKR; // Port configuration lock register -} GPIO_Port; - -typedef volatile uint32* GPIOReg; - -#define POS_MASK(shift) (~(0xF << shift)) -#define POS(val) (val << 2) +#ifndef _GPIO_H_ +#define _GPIO_H_ + +#include "libmaple.h" +#include "rcc.h" #ifdef __cplusplus extern "C"{ #endif -void gpio_init(void); -void gpio_set_mode(GPIO_Port* port, uint8 gpio_pin, GPIOPinMode mode); +/* + * GPIO register maps and devices + */ + +/** GPIO register map type */ +typedef struct gpio_reg_map { + __io uint32 CRL; ///< Port configuration register low + __io uint32 CRH; ///< Port configuration register high + __io uint32 IDR; ///< Port input data register + __io uint32 ODR; ///< Port output data register + __io uint32 BSRR; ///< Port bit set/reset register + __io uint32 BRR; ///< Port bit reset register + __io uint32 LCKR; ///< Port configuration lock register +} gpio_reg_map; + +/** GPIO device type */ +typedef struct gpio_dev { + gpio_reg_map *regs; ///< Register map + rcc_clk_id clk_id; ///< RCC clock information +} gpio_dev; + +/** GPIO port A device */ +extern gpio_dev *GPIOA; +/** GPIO port B device */ +extern gpio_dev *GPIOB; +/** GPIO port C device */ +extern gpio_dev *GPIOC; +/** GPIO port D device */ +extern gpio_dev *GPIOD; +#ifdef STM32_HIGH_DENSITY +/** GPIO port E device */ +extern gpio_dev *GPIOE; +/** GPIO port F device */ +extern gpio_dev *GPIOF; +/** GPIO port G device */ +extern gpio_dev *GPIOG; +#endif + +/** GPIO port A register map base pointer */ +#define GPIOA_BASE ((gpio_reg_map*)0x40010800) +/** GPIO port B register map base pointer */ +#define GPIOB_BASE ((gpio_reg_map*)0x40010C00) +/** GPIO port C register map base pointer */ +#define GPIOC_BASE ((gpio_reg_map*)0x40011000) +/** GPIO port D register map base pointer */ +#define GPIOD_BASE ((gpio_reg_map*)0x40011400) +#ifdef STM32_HIGH_DENSITY +/** GPIO port E register map base pointer */ +#define GPIOE_BASE ((gpio_reg_map*)0x40011800) +/** GPIO port F register map base pointer */ +#define GPIOF_BASE ((gpio_reg_map*)0x40011C00) +/** GPIO port G register map base pointer */ +#define GPIOG_BASE ((gpio_reg_map*)0x40012000) +#endif + +/* + * GPIO register bit definitions + */ + +/* Control registers, low and high */ +#define GPIO_CR_CNF_INPUT_ANALOG (0x0 << 2) +#define GPIO_CR_CNF_INPUT_FLOATING (0x1 << 2) +#define GPIO_CR_CNF_INPUT_PU_PD (0x2 << 2) +#define GPIO_CR_CNF_OUTPUT_PP (0x0 << 2) +#define GPIO_CR_CNF_OUTPUT_OD (0x1 << 2) +#define GPIO_CR_CNF_AF_OUTPUT_PP (0x2 << 2) +#define GPIO_CR_CNF_AF_OUTPUT_OD (0x3 << 2) +#define GPIO_CR_MODE_INPUT 0x0 +#define GPIO_CR_MODE_OUTPUT_10MHZ 0x1 +#define GPIO_CR_MODE_OUTPUT_2MHZ 0x2 +#define GPIO_CR_MODE_OUTPUT_50MHZ 0x3 + +/** GPIO Pin modes. These only allow for 50MHZ max output speeds; if + * you want slower, use direct register access. */ +typedef enum gpio_pin_mode { + GPIO_OUTPUT_PP = (GPIO_CR_CNF_OUTPUT_PP | + GPIO_CR_MODE_OUTPUT_50MHZ), /**< Output push-pull. */ + GPIO_OUTPUT_OD = (GPIO_CR_CNF_OUTPUT_OD | + GPIO_CR_MODE_OUTPUT_50MHZ), /**< Output open-drain. */ + GPIO_AF_OUTPUT_PP = (GPIO_CR_CNF_AF_OUTPUT_PP | + GPIO_CR_MODE_OUTPUT_50MHZ), /**< Alternate function + output push-pull. */ + GPIO_AF_OUTPUT_OD = (GPIO_CR_CNF_AF_OUTPUT_OD | + GPIO_CR_MODE_OUTPUT_50MHZ), /**< Alternate function + output open drain. */ + GPIO_INPUT_ANALOG = (GPIO_CR_CNF_INPUT_ANALOG | + GPIO_CR_MODE_INPUT), /**< Analog input. */ + GPIO_INPUT_FLOATING = (GPIO_CR_CNF_INPUT_FLOATING | + GPIO_CR_MODE_INPUT), /**< Input floating. */ + GPIO_INPUT_PD = (GPIO_CR_CNF_INPUT_PU_PD | + GPIO_CR_MODE_INPUT), /**< Input pull-down. */ + GPIO_INPUT_PU /**< Input pull-up. */ + /* GPIO_INPUT_PU treated as a special case, for ODR twiddling */ +} gpio_pin_mode; -static inline void gpio_write_bit(GPIO_Port *port, uint8 gpio_pin, uint8 val) { - if (val){ - port->BSRR = BIT(gpio_pin); +/* + * GPIO Convenience routines + */ + +void gpio_init(gpio_dev *dev); +void gpio_init_all(void); +void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode); + +/** + * Set or reset a GPIO pin. + * + * Pin must have previously been configured to output mode. + * + * @param dev GPIO device whose pin to set. + * @param pin Pin on to set or reset + * @param val If true, set the pin. If false, reset the pin. + */ +static inline void gpio_write_bit(gpio_dev *dev, uint8 pin, uint8 val) { + if (val) { + dev->regs->BSRR = BIT(pin); } else { - port->BRR = BIT(gpio_pin); + dev->regs->BRR = BIT(pin); } } -static inline uint32 gpio_read_bit(GPIO_Port *port, uint8 gpio_pin) { - return (port->IDR & BIT(gpio_pin) ? 1 : 0); +/** + * Determine whether or not a GPIO pin is set. + * + * Pin must have previously been configured to input mode. + * + * @param dev GPIO device whose pin to test. + * @param pin Pin on dev to test. + * @return True if the pin is set, false otherwise. + */ +static inline uint32 gpio_read_bit(gpio_dev *dev, uint8 pin) { + return dev->regs->IDR & BIT(pin); } -/* For pins configured as output push-pull, reading the ODR returns - * the last value written in push-pull mode. +/** + * Toggle a pin configured as output push-pull. + * @param dev GPIO device. + * @param pin Pin on dev to toggle. */ -static inline void gpio_toggle_pin(GPIO_Port *port, uint8 gpio_pin) { - port->ODR = port->ODR ^ BIT(gpio_pin); +static inline void gpio_toggle_bit(gpio_dev *dev, uint8 pin) { + dev->regs->ODR = dev->regs->ODR ^ BIT(pin); } -#ifdef __cplusplus -} // extern "C" +/* + * AFIO register map + */ + +/** AFIO register map */ +typedef struct afio_reg_map { + __io uint32 EVCR; /**< Event control register. */ + __io uint32 MAPR; /**< AF remap and debug I/O configuration + register. */ + __io uint32 EXTICR1; /**< External interrupt configuration + register 1. */ + __io uint32 EXTICR2; /**< External interrupt configuration + register 2. */ + __io uint32 EXTICR3; /**< External interrupt configuration + register 3. */ + __io uint32 EXTICR4; /**< External interrupt configuration + register 4. */ + __io uint32 MAPR2; /**< AF remap and debug I/O configuration + register 2. */ +} afio_reg_map; + +/** AFIO register map base pointer. */ +#define AFIO_BASE ((afio_reg_map *)0x40010000) + +/* + * AFIO register bit definitions + */ + +/* Event control register */ +#define AFIO_EVCR_EVOE (0x1 << 7) +#define AFIO_EVCR_PORT_PA (0x0 << 4) +#define AFIO_EVCR_PORT_PB (0x1 << 4) +#define AFIO_EVCR_PORT_PC (0x2 << 4) +#define AFIO_EVCR_PORT_PD (0x3 << 4) +#define AFIO_EVCR_PORT_PE (0x4 << 4) +#define AFIO_EVCR_PIN_0 0x0 +#define AFIO_EVCR_PIN_1 0x1 +#define AFIO_EVCR_PIN_2 0x2 +#define AFIO_EVCR_PIN_3 0x3 +#define AFIO_EVCR_PIN_4 0x4 +#define AFIO_EVCR_PIN_5 0x5 +#define AFIO_EVCR_PIN_6 0x6 +#define AFIO_EVCR_PIN_7 0x7 +#define AFIO_EVCR_PIN_8 0x8 +#define AFIO_EVCR_PIN_9 0x9 +#define AFIO_EVCR_PIN_10 0xA +#define AFIO_EVCR_PIN_11 0xB +#define AFIO_EVCR_PIN_12 0xC +#define AFIO_EVCR_PIN_13 0xD +#define AFIO_EVCR_PIN_14 0xE +#define AFIO_EVCR_PIN_15 0xF + +/* AF remap and debug I/O configuration register */ +#define AFIO_MAPR_SWJ_FULL_SWJ (0x0 << 24) +#define AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (0x1 << 24) +#define AFIO_MAPR_SWJ_NO_JTAG_SW (0x2 << 24) +#define AFIO_MAPR_SWJ_NO_JTAG_NO_SW (0x4 << 24) +#define AFIO_MAPR_ADC2_ETRGREG_REMAP BIT(20) +#define AFIO_MAPR_ADC2_ETRGINJ_REMAP BIT(19) +#define AFIO_MAPR_ADC1_ETRGREG_REMAP BIT(18) +#define AFIO_MAPR_ADC1_ETRGINJ_REMAP BIT(17) +#define AFIO_MAPR_TIM5CH4_IREMAP BIT(16) +#define AFIO_MAPR_PD01_REMAP BIT(15) +#define AFIO_MAPR_CAN_REMAP (BIT(14) | BIT(13)) +#define AFIO_MAPR_TIM4_REMAP_FULL BIT(12) +#define AFIO_MAPR_TIM3_REMAP (BIT(11) | BIT(10)) +#define AFIO_MAPR_TIM2_REMAP (BIT(9) | BIT(8)) +#define AFIO_MAPR_TIM1_REMAP (BIT(7) | BIT(6)) +#define AFIO_MAPR_USART3_REMAP (BIT(5) | BIT(4)) +#define AFIO_MAPR_USART2_REMAP BIT(3) +#define AFIO_MAPR_USART1_REMAP BIT(2) +#define AFIO_MAPR_I2C1_REMAP BIT(1) +#define AFIO_MAPR_SPI1_REMAP BIT(0) + +/* External interrupt configuration registers */ + +/** + * External interrupt line port selector. Used to determine which + * GPIO port to map an external interrupt line onto. */ +typedef enum { + AFIO_EXTI_PA, /**< Use PAx pin. */ + AFIO_EXTI_PB, /**< Use PBx pin. */ + AFIO_EXTI_PC, /**< Use PCx pin. */ + AFIO_EXTI_PD, /**< Use PDx pin. */ +#ifdef STM32_HIGH_DENSITY + AFIO_EXTI_PE, /**< Use PEx pin. */ + AFIO_EXTI_PF, /**< Use PFx pin. */ + AFIO_EXTI_PG, /**< Use PGx pin. */ #endif +} afio_exti_port; + +/** + * External interrupt line numbers. + */ +typedef enum { + AFIO_EXTI_0, /**< External interrupt line 0. */ + AFIO_EXTI_1, /**< External interrupt line 1. */ + AFIO_EXTI_2, /**< External interrupt line 2. */ + AFIO_EXTI_3, /**< External interrupt line 3. */ + AFIO_EXTI_4, /**< External interrupt line 4. */ + AFIO_EXTI_5, /**< External interrupt line 5. */ + AFIO_EXTI_6, /**< External interrupt line 6. */ + AFIO_EXTI_7, /**< External interrupt line 7. */ + AFIO_EXTI_8, /**< External interrupt line 8. */ + AFIO_EXTI_9, /**< External interrupt line 9. */ + AFIO_EXTI_10, /**< External interrupt line 10. */ + AFIO_EXTI_11, /**< External interrupt line 11. */ + AFIO_EXTI_12, /**< External interrupt line 12. */ + AFIO_EXTI_13, /**< External interrupt line 13. */ + AFIO_EXTI_14, /**< External interrupt line 14. */ + AFIO_EXTI_15, /**< External interrupt line 15. */ +} afio_exti_num; +/* AF remap and debug I/O configuration register 2 */ +#define AFIO_MAPR2_FSMC_NADV BIT(10) +#define AFIO_MAPR2_TIM14_REMAP BIT(9) +#define AFIO_MAPR2_TIM13_REMAP BIT(8) +#define AFIO_MAPR2_TIM11_REMAP BIT(7) +#define AFIO_MAPR2_TIM10_REMAP BIT(6) +#define AFIO_MAPR2_TIM9_REMAP BIT(5) + +/* + * AFIO convenience routines + */ + +void afio_init(void); +void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port); + +/** + * Set the SWJ_CONFIG bits in the AFIO MAPR register. + * + * @param config Desired SWJ_CONFIG bits setting. One of: + * AFIO_MAPR_SWJ_FULL_SWJ (full SWJ), + * AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (full SWJ, no NJTRST), + * AFIO_MAPR_SWJ_NO_JTAG_SW (JTAG-DP disabled, SW-DP enabled), + * AFIO_MAPR_SWJ_NO_JTAG_NO_SW (JTAG-DP and SW-DP both disabled). + */ +static inline void afio_mapr_swj_config(uint32 config) { + __io uint32 *mapr = &AFIO_BASE->MAPR; + *mapr = (*mapr & ~(0x7 << 24)) | config; +} + +#ifdef __cplusplus +} +#endif #endif diff --git a/libmaple/libmaple.h b/libmaple/libmaple.h index 6b75c96..0bbd34e 100644 --- a/libmaple/libmaple.h +++ b/libmaple/libmaple.h @@ -36,7 +36,7 @@ /* * Where to put usercode, based on space reserved for bootloader. * - * FIXME this has no business being here + * FIXME this has no business being here */ #define USER_ADDR_ROM 0x08005000 #define USER_ADDR_RAM 0x20000C00 diff --git a/libmaple/libmaple_types.h b/libmaple/libmaple_types.h index a976a9e..54bef65 100644 --- a/libmaple/libmaple_types.h +++ b/libmaple/libmaple_types.h @@ -44,6 +44,7 @@ typedef long long int64; typedef void (*voidFuncPtr)(void); #define __io volatile +#define __attr_flash __attribute__((section (".USER_FLASH"))) #ifndef NULL #define NULL 0 diff --git a/libmaple/pwr.h b/libmaple/pwr.h index 5ff815d..5f68c34 100644 --- a/libmaple/pwr.h +++ b/libmaple/pwr.h @@ -41,20 +41,19 @@ typedef struct pwr_reg_map { __io uint32 CSR; /**< Control and status register */ } pwr_reg_map; -/* - * Power peripheral base. - */ +/** Power peripheral register map base pointer. */ #define PWR_BASE ((pwr_reg_map*)0x40007000) -/** Power interface device. */ +/** Power device type. */ typedef struct pwr_dev { - pwr_reg_map *regs; + pwr_reg_map *regs; /**< Register map */ } pwr_dev; /** * Power device. */ extern const pwr_dev *PWR; + /* * Register bit definitions */ diff --git a/libmaple/rcc.h b/libmaple/rcc.h index 410ab8b..8697e01 100644 --- a/libmaple/rcc.h +++ b/libmaple/rcc.h @@ -27,6 +27,8 @@ * @brief reset and clock control definitions and prototypes */ +#include "libmaple_types.h" + #ifndef _RCC_H_ #define _RCC_H_ @@ -182,7 +184,6 @@ typedef enum { RCC_BKP, } rcc_clk_id; - void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul); void rcc_clk_enable(rcc_clk_id device); void rcc_reset_dev(rcc_clk_id device); diff --git a/libmaple/ring_buffer.h b/libmaple/ring_buffer.h index a44088e..f7baa6c 100644 --- a/libmaple/ring_buffer.h +++ b/libmaple/ring_buffer.h @@ -13,21 +13,20 @@ extern "C"{ #endif -/* The buffer is empty when head == tail. +/** + * Ring buffer type. + * + * The buffer is empty when head == tail. * * The buffer is full when the head is one byte in front of the tail, * modulo buffer length. * * One byte is left free to distinguish empty from full. */ typedef struct ring_buffer { - /** Buffer items are stored into */ - volatile uint8 *buf; - /** Index of the next item to remove */ - uint16 head; - /** Index where the next item will get inserted */ - uint16 tail; - /** Buffer capacity minus one */ - uint16 size; + volatile uint8 *buf; /**< Buffer items are stored into */ + uint16 head; /**< Index of the next item to remove */ + uint16 tail; /**< Index where the next item will get inserted */ + uint16 size; /**< Buffer capacity minus one */ } ring_buffer; /** diff --git a/libmaple/spi.c b/libmaple/spi.c index 8bba0d6..7bdc18a 100644 --- a/libmaple/spi.c +++ b/libmaple/spi.c @@ -43,23 +43,23 @@ typedef struct spi_dev { SPI *base; - GPIO_Port *port; + gpio_dev *gpio_d; uint8 sck_pin; uint8 miso_pin; uint8 mosi_pin; } spi_dev; -static const spi_dev spi_dev1 = { +spi_dev spi_dev1 = { .base = (SPI*)SPI1_BASE, - .port = GPIOA_BASE, + .gpio_d = NULL, .sck_pin = 5, .miso_pin = 6, .mosi_pin = 7 }; -static const spi_dev spi_dev2 = { +spi_dev spi_dev2 = { .base = (SPI*)SPI2_BASE, - .port = GPIOB_BASE, + .gpio_d = NULL, .sck_pin = 13, .miso_pin = 14, .mosi_pin = 15 @@ -90,11 +90,13 @@ void spi_init(uint32 spi_num, ASSERT(prescale != CR1_BR_PRESCALE_2); spi = (SPI*)SPI1_BASE; rcc_clk_enable(RCC_SPI1); + spi_dev1.gpio_d = GPIOA; spi_gpio_cfg(&spi_dev1); break; case 2: spi = (SPI*)SPI2_BASE; rcc_clk_enable(RCC_SPI2); + spi_dev1.gpio_d = GPIOB, spi_gpio_cfg(&spi_dev2); break; } @@ -155,7 +157,7 @@ uint8 spi_tx(uint32 spi_num, uint8 *buf, uint32 len) { } static void spi_gpio_cfg(const spi_dev *dev) { - gpio_set_mode(dev->port, dev->sck_pin, GPIO_MODE_AF_OUTPUT_PP); - gpio_set_mode(dev->port, dev->miso_pin, GPIO_MODE_AF_OUTPUT_PP); - gpio_set_mode(dev->port, dev->mosi_pin, GPIO_MODE_AF_OUTPUT_PP); + gpio_set_mode(dev->gpio_d, dev->sck_pin, GPIO_AF_OUTPUT_PP); + gpio_set_mode(dev->gpio_d, dev->miso_pin, GPIO_AF_OUTPUT_PP); + gpio_set_mode(dev->gpio_d, dev->mosi_pin, GPIO_AF_OUTPUT_PP); } diff --git a/libmaple/usb/usb.c b/libmaple/usb/usb.c index 62f56fc..2fc4eb2 100644 --- a/libmaple/usb/usb.c +++ b/libmaple/usb/usb.c @@ -44,7 +44,7 @@ volatile uint32 bDeviceState = UNCONNECTED; volatile uint16 wIstr = 0; -volatile bIntPackSOF = 0; +volatile uint32 bIntPackSOF = 0; DEVICE Device_Table = {NUM_ENDPTS, @@ -99,15 +99,13 @@ struct { } ResumeS; void setupUSB (void) { - gpio_set_mode(USB_DISC_BANK, - USB_DISC_PIN, - GPIO_MODE_OUTPUT_PP); + gpio_set_mode(USB_DISC_DEV, USB_DISC_PIN, GPIO_OUTPUT_PP); /* setup the apb1 clock for USB */ pRCC->APB1ENR |= 0x00800000; /* initialize the usb application */ - gpio_write_bit(USB_DISC_BANK, USB_DISC_PIN, 0); // presents us to the host + gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN, 0); // presents us to the host USB_Init(); // low level init routine provided by the ST library } @@ -115,7 +113,7 @@ void disableUSB (void) { // These are just guesses about how to do this // TODO: real disable function usbDsbISR(); - gpio_write_bit(USB_DISC_BANK,USB_DISC_PIN,1); + gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN, 1); } void usbSuspend(void) { @@ -320,8 +318,29 @@ if (wIstr & ISTR_CTR & wInterrupt_Mask) { } +static void FIXME_delayMicroseconds_copy(uint32 us) { + /* So (2^32)/12 micros max, or less than 6 minutes */ + us *= 12; + + /* fudge for function call overhead */ + us--; + asm volatile(" mov r0, %[us] \n\t" + "1: subs r0, #1 \n\t" + " bhi 1b \n\t" + : + : [us] "r" (us) + : "r0"); +} + +static void FIXME_delay_copy(unsigned long ms) { + uint32 i; + for (i = 0; i < ms; i++) { + FIXME_delayMicroseconds_copy(1000); + } +} + void usbWaitReset(void) { - delay(RESET_DELAY); + FIXME_delay_copy(RESET_DELAY); systemHardReset(); } diff --git a/libmaple/usb/usb_callbacks.c b/libmaple/usb/usb_callbacks.c index ccb0fdd..8184537 100644 --- a/libmaple/usb/usb_callbacks.c +++ b/libmaple/usb/usb_callbacks.c @@ -129,7 +129,7 @@ u8* vcomGetSetLineCoding(uint16 length) { return (uint8*)&line_coding; } -vcomSetLineState(void) { +void vcomSetLineState(void) { } void usbInit(void) { diff --git a/libmaple/usb/usb_config.h b/libmaple/usb/usb_config.h index 394c580..9003da9 100644 --- a/libmaple/usb/usb_config.h +++ b/libmaple/usb/usb_config.h @@ -4,6 +4,7 @@ #define __USB_CONFIG_H #include "usb_lib.h" +#include "gpio.h" /****************************************************************************** ****************************************************************************** @@ -31,19 +32,19 @@ /* USB Identifier numbers */ #define VCOM_ID_PRODUCT 0x0004 - #define USB_DISC_BANK GPIOC_BASE + #define USB_DISC_DEV GPIOC #define USB_DISC_PIN 12 #elif defined(BOARD_maple_mini) #define VCOM_ID_PRODUCT 0x0005 - #define USB_DISC_BANK GPIOB_BASE + #define USB_DISC_DEV GPIOB #define USB_DISC_PIN 9 #elif defined(BOARD_maple_native) #define VCOM_ID_PRODUCT 0x0006 - #define USB_DISC_BANK GPIOB_BASE + #define USB_DISC_DEV GPIOB #define USB_DISC_PIN 8 #else diff --git a/libmaple/usb/usb_hardware.c b/libmaple/usb/usb_hardware.c index 505dcf1..9a7d12c 100644 --- a/libmaple/usb/usb_hardware.c +++ b/libmaple/usb/usb_hardware.c @@ -33,47 +33,6 @@ #include "usb_hardware.h" -void setPin(u32 bank, u8 pin) { - u32 pinMask = 0x1 << (pin); - SET_REG(GPIO_BSRR(bank),pinMask); -} - -void resetPin(u32 bank, u8 pin) { - u32 pinMask = 0x1 << (16+pin); - SET_REG(GPIO_BSRR(bank),pinMask); -} - -void systemReset(void) { - SET_REG(RCC_CR, GET_REG(RCC_CR) | 0x00000001); - SET_REG(RCC_CFGR, GET_REG(RCC_CFGR) & 0xF8FF0000); - SET_REG(RCC_CR, GET_REG(RCC_CR) & 0xFEF6FFFF); - SET_REG(RCC_CR, GET_REG(RCC_CR) & 0xFFFBFFFF); - SET_REG(RCC_CFGR, GET_REG(RCC_CFGR) & 0xFF80FFFF); - - SET_REG(RCC_CIR, 0x00000000); // disable all RCC interrupts -} - -void setupCLK (void) { - /* enable HSE */ - SET_REG(RCC_CR,GET_REG(RCC_CR) | 0x00010001); - /* for it to come on */ - while ((GET_REG(RCC_CR) & 0x00020000) == 0); - - /* Configure PLL */ - /* pll=72Mhz,APB1=36Mhz,AHB=72Mhz */ - SET_REG(RCC_CFGR,GET_REG(RCC_CFGR) | 0x001D0400); - /* enable the pll */ - SET_REG(RCC_CR,GET_REG(RCC_CR) | 0x01000000); - /* wait for it to come on */ - while ((GET_REG(RCC_CR) & 0x03000000) == 0); - - /* Set SYSCLK as PLL */ - SET_REG(RCC_CFGR,GET_REG(RCC_CFGR) | 0x00000002); - /* wait for it to come on */ - while ((GET_REG(RCC_CFGR) & 0x00000008) == 0); -} - - void nvicInit(NVIC_InitTypeDef* NVIC_InitStruct) { u32 tmppriority = 0x00; u32 tmpreg = 0x00; diff --git a/libmaple/usb/usb_hardware.h b/libmaple/usb/usb_hardware.h index e4a26b4..cfead1a 100644 --- a/libmaple/usb/usb_hardware.h +++ b/libmaple/usb/usb_hardware.h @@ -22,34 +22,20 @@ * THE SOFTWARE. * ****************************************************************************/ -#ifndef __HARDWARE_H -#define __HARDWARE_H - +#include "rcc.h" #include "usb_type.h" +#ifndef _USB_HARDWARE_H_ +#define _USB_HARDWARE_H_ + /* macro'd register and peripheral definitions */ #define EXC_RETURN 0xFFFFFFF9 #define DEFAULT_CPSR 0x61000000 -#define RCC ((u32)0x40021000) #define FLASH ((u32)0x40022000) -#define GPIOA ((u32)0x40010800) -#define GPIOC ((u32)0x40011000) #define USB_PACKET_BUFFER ((u32)0x40006000) -#define RCC_CR RCC -#define RCC_CFGR RCC + 0x04 -#define RCC_CIR RCC + 0x08 -#define RCC_AHBENR RCC + 0x14 -#define RCC_APB2ENR RCC + 0x18 -#define RCC_APB1ENR RCC + 0x16 - -#define GPIO_CRL(port) port -#define GPIO_CRH(port) port+0x04 -#define GPIO_ODR(port) port+0x0c -#define GPIO_BSRR(port) port+0x10 - #define SCS_BASE ((u32)0xE000E000) #define NVIC_BASE (SCS_BASE + 0x0100) #define SCB_BASE (SCS_BASE + 0x0D00) @@ -74,9 +60,8 @@ #define __PSC(__TIMCLK, __PERIOD) (((__VAL(__TIMCLK, __PERIOD)+49999UL)/50000UL) - 1) #define __ARR(__TIMCLK, __PERIOD) ((__VAL(__TIMCLK, __PERIOD)/(__PSC(__TIMCLK, __PERIOD)+1)) - 1) -/* todo, wrap in do whiles for the natural ; */ -#define SET_REG(addr,val) *(vu32*)(addr)=val -#define GET_REG(addr) *(vu32*)(addr) +#define SET_REG(addr,val) do { *(vu32*)(addr)=val; } while (0) +#define GET_REG(addr) do { *(vu32*)(addr); } while (0) #if defined(__cplusplus) extern "C" { @@ -85,7 +70,7 @@ extern "C" { /* todo: there must be some major misunderstanding in how we access regs. The direct access approach (GET_REG) causes the usb init to fail upon trying to activate RCC_APB1 |= 0x00800000. However, using the struct approach from ST, it works fine...temporarily switching to that approach */ -typedef struct +typedef struct { vu32 CR; vu32 CFGR; @@ -98,7 +83,7 @@ typedef struct vu32 BDCR; vu32 CSR; } RCC_RegStruct; -#define pRCC ((RCC_RegStruct *) RCC) +#define pRCC ((RCC_RegStruct *) RCC_BASE) typedef struct { vu32 ISER[2]; @@ -139,12 +124,7 @@ typedef struct { } SCB_TypeDef; -void setPin (u32 bank, u8 pin); -void resetPin (u32 bank, u8 pin); - void systemHardReset(void); -void systemReset (void); -void setupCLK (void); void nvicInit (NVIC_InitTypeDef*); void nvicDisableInterrupts(void); diff --git a/libmaple/util.c b/libmaple/util.c index 3408a2e..09fbecd 100644 --- a/libmaple/util.c +++ b/libmaple/util.c @@ -38,7 +38,7 @@ #ifndef ERROR_USART_NUM #define ERROR_USART_NUM USART2 #define ERROR_USART_BAUD 9600 -#define ERROR_TX_PORT GPIOA_BASE +#define ERROR_TX_PORT GPIOA #define ERROR_TX_PIN 2 #endif @@ -87,7 +87,7 @@ void __error(void) { */ void _fail(const char* file, int line, const char* exp) { /* Initialize the error usart */ - gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_MODE_AF_OUTPUT_PP); + gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_AF_OUTPUT_PP); usart_init(ERROR_USART_NUM, ERROR_USART_BAUD); /* Print failed assert message */ @@ -116,7 +116,7 @@ void throb(void) { uint32 TOP_CNT = 0x0200; uint32 i = 0; - gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_MODE_OUTPUT_PP); + gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_OUTPUT_PP); /* Error fade */ while (1) { if (CC == TOP_CNT) { diff --git a/libmaple/util.h b/libmaple/util.h index fb524c2..25dd56e 100644 --- a/libmaple/util.h +++ b/libmaple/util.h @@ -28,6 +28,8 @@ * @brief Various macros and utility procedures. */ +#include "libmaple_types.h" + /* Generally "useful" utility procedures */ #ifndef _UTIL_H_ #define _UTIL_H_ @@ -51,40 +53,29 @@ extern "C"{ /* Return bits m to n of x */ #define GET_BITS(x, m, n) ((((uint32)x) << (31 - (n))) >> ((31 - (n)) + (m))) -/* Bit-banding macros */ -/* Bitbanded Memory sections */ -#define BITBAND_SRAM_REF 0x20000000 -#define BITBAND_SRAM_BASE 0x22000000 -#define BITBAND_PERI_REF 0x40000000 -#define BITBAND_PERI_BASE 0x42000000 -/* Convert SRAM address */ -#define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE+(a-BITBAND_SRAM_REF)*32+(b*4))) -/* Convert peripheral address */ -#define BITBAND_PERI(a, b) ((BITBAND_PERI_BASE + \ - ((uint32)a - BITBAND_PERI_REF) * 32 + (b * 4))) - -#define REG_SET(reg, val) (*(volatile uint32*)(reg) = (val)) -#define REG_SET_BIT(reg, bit) (*(volatile uint32*)(reg) |= BIT(bit)) -#define REG_CLEAR_BIT(reg, bit) (*(volatile uint32*)(reg) &= ~BIT(bit)) -#define REG_SET_MASK(reg, mask) (*(volatile uint32*)(reg) |= (uint32)(mask)) -#define REG_CLEAR_MASK(reg, mask) (*(volatile uint32*)(reg) &= (uint32)~(mask)) - -#define REG_GET(reg) (*(volatile uint32*)(reg)) +/* + * Register reads and writes + */ #define __set_bits(addr, mask) (*(volatile uint32*)(addr) |= (uint32)(mask)) #define __clear_bits(addr, mask) (*(volatile uint32*)(addr) &= (uint32)~(mask)) #define __get_bits(addr, mask) (*(volatile uint32*)(addr) & (uint32)(mask)) - #define __read(reg) (*(volatile uint32*)(reg)) #define __write(reg, value) (*(volatile uint32*)(reg) = (value)) #define IS_POWER_OF_TWO(v) (v && !(v & (v - 1))) + +/* + * Failure routines + */ + void __error(void); void _fail(const char*, int, const char*); void throb(void); -/* Asserts for sanity checks, redefine DEBUG_LEVEL in libmaple.h to - * compile out these checks */ +/* + * Asserts and debug levels + */ #if DEBUG_LEVEL >= DEBUG_ALL #define ASSERT(exp) \ diff --git a/notes/coding_standard.txt b/notes/coding_standard.txt index 5cb96c3..372ebf4 100644 --- a/notes/coding_standard.txt +++ b/notes/coding_standard.txt @@ -25,12 +25,11 @@ License ------- - Put an MIT license at the beginning of the file (look at any of our - source files for an example). Copyright should go to either you or - LeafLabs LLC. + source files for an example). Copyright should go either to you or + to LeafLabs, LLC. Emacs: if you don't like seeing the license, you should use - elide-head (which will hide it for you). Here is some elisp you can - modify to make this pleasant: + elide-head (which will hide it for you). You can use the following: (require 'elide-head) (setq programming-mode-hooks '(c-mode-hook c++-mode-hook)) @@ -38,7 +37,7 @@ License '("The MIT License" . "DEALINGS IN\n [*] THE SOFTWARE")) (add-to-list 'elide-head-headers-to-hide '("The MIT License" . "DEALINGS IN THE\n...SOFTWARE")) - (dolist (hook mbolivar-programming-mode-hooks) + (dolist (hook programming-mode-hooks) (add-hook hook (lambda () (elide-head)))) Whitespace/Indentation @@ -46,7 +45,8 @@ Whitespace/Indentation - 4 space indents. [Set in .dir-locals.el] -- Unix newlines. +- Unix newlines. [Some exceptions are currently grandfathered in; + these will go away in time.] - No tab characters. [Set in .dir-locals.el] @@ -76,50 +76,53 @@ Whitespace/Indentation (add-hook 'c-mode-hook c-mode-inextern-lang-hook) - Comments -------- -- Multi-line comments look like this: +- Multi-line comments are pretty flexible. Any of these is fine: - /* text starts here - * continued lines have a '*' before them - * the comment can end after the last line + /* Comment starts here. + * Continued lines have a '*' before them. + * The comment can end after the last line. */ - or this: - - /* comment starts here - * the comment can end on the same line */ + /* Comment starts here. + * The comment can end on the same line. */ -- Doxygen comments are newline comments that begin with /** instead. - It is not required that the "/**" appear on a line by itself. + /* + * You can also place a newline after the opening "/*". + */ -- Single-line comments on the same line are // in c or c++. +- Doxygen comments are multi-line comments that begin with /** instead. -- Single-line comments on their own source line are /* */ in c, but - can also be // in c++. If you think that typing out /* */ is too - slow in emacs, use M-; (comment-dwim) when you're on an empty line, - and it'll ... well... +- Single-line comments on the same line are // in C or C++. - You should be using the (super awesome) comment-dwim; it pretty - much does exactly what you want to the comment on the current - line, including "create one and put it in the right place". +- Single-line comments on their own source line should be /* */ in C, + but can also be // in C++. In Emacs, you can use M-; + (comment-dwim), and it'll Do What You Mean. Braces ------ -- 1TBS. Nothing more need be said. +- Mostly 1TBS: http://en.wikipedia.org/wiki/Indent_style#Variant:_1TBS + The only difference is that the opening brace of a function's + definition occurs exactly one space character after the closing + parenthesis in that function's parameter list. Example: + + void func(void) { + ... + } + Naming conventions ------------------ -- There's always a fight about upper and lower case vs. underscores. - We'll handle this as follows. +There's always a fight about upper and lower case vs. underscores. +We'll handle this as follows. - First, Dammit_Dont_Mix_Like_This, because It_Looks_Really_Ugly, ok? +- First, Dammit_Dont_Mix_Like_This, because It_Looks_Really_Ugly, ok? [There's been some debate about this, and some exceptions are already grandfathered in, so in order to settle it, let's call this a "recommendation" instead of "requirement".] @@ -168,7 +171,7 @@ Naming conventions Documentation ------------- -- Document your code. This should go without saying. +- Document your code! - For complicated peripherals, it would be nice if you put longer-form comments into this directory (notes/), with a comment in the @@ -176,13 +179,8 @@ Documentation example. That lets us keep the source files relatively clean while still allowing new readers to have a starting point. -- At least put a doxygen comment with a nonempty @brief for every .h - file you add. See the existing ones for examples. For now, it'd be - better if you didn't put a @brief into any .c[pp] files, since it - (currently) interferes with our documentation generator in a way - that I won't explain here (though you can look into the LeafLabs or - michaeljones breathe repos on github and potentially figure out - why). +- At least put a Doxygen comment with a nonempty @brief for every .h + file you add. See the existing ones for examples. - Doxygen comments generally just belong on types, functions, etc. that are part of the public user-facing API. This generally @@ -196,8 +194,13 @@ Documentation This should be avoided if at all possible, since it creates a maintenance burden of documenting things in two places at once, and - provides an opportunity for bad documentation to slip in, when the - code comments fall out of sync with the ReST docs. + makes it easier for documentation to go stale. + +- For libmaple proper (the pure C library under libmaple/); the + convention is to document any user-facing entity at the point where + it is defined. In particular, this means you should document an + externally-linked function defined in a .c file in that .c file, not + in the header file where it is declared to the user. General Formatting ------------------ @@ -217,7 +220,3 @@ General Formatting (require 'lineker) (dolist (hook '(c-mode-hook c++-mode-hook)) (add-hook hook (lambda () (lineker-mode 1)))) - - There are only a few exceptional situations. The most important one - is when specifying a lookup table like PIN_MAP where it'd be ugly to - split each entry over multiple lines. diff --git a/notes/exti.txt b/notes/exti.txt new file mode 100644 index 0000000..1ad49ee --- /dev/null +++ b/notes/exti.txt @@ -0,0 +1,67 @@ +External interrupt notes. + +To generate the interrupt, the interrupt line should be configured +and enabled. This is done by programming the two trigger registers +with the desired edge detection and by enabling the interrupt +request by writing a '1' to the corresponding bit in the interrupt +mask register. When the selected edge occurs on the external +interrupt line, an interrupt request is generated. The pending bit +corresponding to the interrupt line is also set. This request is +reset by writing a '1' in the pending register. + +Hardware interrupt selection: + +To configure the 20 lines as interrupt sources, use the following +procedure: + +1) Configure AFIO_EXTICR[y] to select the source input for EXTIx + external interrupt +2) Configure the mask bits of the 20 interrupt lines (EXTI_IMR) +3) Configure the trigger selection bits of the interrupt lines + (EXTI_RTSR and EXTI_FTSR) +4) Configure the enable and mask bits that control the NVIC_IRQ + channel mapped to the External Interrupt Controller (EXTI) so + that an inerrupt coming from one of the 20 lines can be + correctly acknowledged. + +AFIO clock must be on. + +RM0008, page 107: "PD0, PD1 cannot be used for external +interrupt/event generation on 36, 48, 64-bin packages." + +---------------------------------------------------------------------------- +Pin to EXTI Line Mappings: +EXTI0 EXTI1 EXTI2 EXTI3 EXTI4 +-------------------------------------------------------------------------- +D2/PA0 D3/PA1 D1/PA2 D0/A6/PA3 D10/A10/PA4 +D26/EXT7/PB0 D27/EXT8/PB1 D16/A2/PC2 D17/A3/PC3 D18/A4/PC4 +D14/A0/PC0 D15/PC1 D25/EXT5/PD2 + +EXTI5 EXTI6 EXTI7 EXTI8 EXTI9 +---------------------------------------------------------------------------- +D13/A13/PA5 D12/A12/PA6 D11/A11/PA7 D6/PA8 D7/PA9 +D4/PB5 D5/PB6 D9/PB7 D38/PB8 D23/EXT4/PB9 +D19/A5/PC5 D34/EXTI15/PC6 D35/EXT16/PC7 D36/PC8 D37/EXT18/PC9 + +EXTI10 EXTI11 EXTI12 EXTI13 EXTI14 +---------------------------------------------------------------------------- +D8/PA10 D29/EXT10/PB11 D30/EXTI1/PB12 D31/EXTI12/PB13 D32/EXT13/PB14 +D28/PB10 D20/EXTI1/PC13 D21/EXT2/PC14 +D25/PC10 + +EXTI15 +---------------------------------------------------------------------------- +D33/EXTI14/PB15 +D22/EXT3/PC15 + + +The 16 EXTI interrupts are mapped to 7 interrupt handlers. + +EXTI Lines to Interrupt Mapping: +EXTI0 -> EXTI0 +EXTI1 -> EXTI1 +EXTI2 -> EXTI2 +EXTI3 -> EXTI3 +EXTI4 -> EXTI4 +EXTI[5-9] -> EXT9_5 +EXTI[10-15] -> EXT15_10 diff --git a/wirish/HardwareTimer.cpp b/wirish/HardwareTimer.cpp index 0f8bec6..04d1c76 100644 --- a/wirish/HardwareTimer.cpp +++ b/wirish/HardwareTimer.cpp @@ -89,7 +89,7 @@ uint16 HardwareTimer::setPeriod(uint32 microseconds) { return this->getOverflow(); } -inline void HardwareTimer::setChannelMode(int channel, TimerMode mode) { +void HardwareTimer::setChannelMode(int channel, TimerMode mode) { timer_set_mode(this->timerNum, channel, mode); } @@ -109,7 +109,7 @@ void HardwareTimer::setChannel4Mode(TimerMode mode) { this->setChannelMode(4, mode); } -inline uint16 HardwareTimer::getCompare(int channel) { +uint16 HardwareTimer::getCompare(int channel) { return timer_get_compare_value(this->timerNum, channel); } @@ -129,7 +129,7 @@ uint16 HardwareTimer::getCompare4() { return this->getCompare(4); } -inline void HardwareTimer::setCompare(int channel, uint16 val) { +void HardwareTimer::setCompare(int channel, uint16 val) { uint16 ovf = this->getOverflow(); timer_set_compare_value(this->timerNum, channel, min(val, ovf)); } @@ -150,7 +150,7 @@ void HardwareTimer::setCompare4(uint16 val) { this->setCompare(4, val); } -inline void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) { +void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) { timer_attach_interrupt(this->timerNum, channel, handler); } @@ -170,7 +170,7 @@ void HardwareTimer::attachCompare4Interrupt(voidFuncPtr handler) { this->attachInterrupt(4, handler); } -inline void HardwareTimer::detachInterrupt(int channel) { +void HardwareTimer::detachInterrupt(int channel) { timer_detach_interrupt(this->timerNum, channel); } @@ -194,7 +194,6 @@ void HardwareTimer::generateUpdate(void) { timer_generate_update(this->timerNum); } - HardwareTimer Timer1(TIMER1); HardwareTimer Timer2(TIMER2); HardwareTimer Timer3(TIMER3); diff --git a/wirish/boards.cpp b/wirish/boards.cpp new file mode 100644 index 0000000..9276f36 --- /dev/null +++ b/wirish/boards.cpp @@ -0,0 +1,387 @@ +#include "boards.h" + +// think of the poor column numbers +#define ADCx ADC_INVALID +#define TIMERx TIMER_INVALID + +#if defined(BOARD_maple) + +PinMapping PIN_MAP[NR_GPIO_PINS] = { + /* D0/PA3 */ + {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, + /* D1/PA2 */ + {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, + /* D2/PA0 */ + {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, + /* D3/PA1 */ + {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, + /* D4/PB5 */ + {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D5/PB6 */ + {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, + /* D6/PA8 */ + {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, + /* D7/PA9 */ + {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, + /* D8/PA10 */ + {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, + /* D9/PB7 */ + {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, + /* D10/PA4 */ + {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D11/PA7 */ + {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, + /* D12/PA6 */ + {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, + /* D13/PA5 */ + {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D14/PB8 */ + {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, + + /* Little header */ + + /* D15/PC0 */ + {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D16/PC1 */ + {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D17/PC2 */ + {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D18/PC3 */ + {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D19/PC4 */ + {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D20/PC5 */ + {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + + /* External header */ + + /* D21/PC13 */ + {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D22/PC14 */ + {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D23/PC15 */ + {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D24/PB9 */ + {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, + /* D25/PD2 */ + {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D26/PC10 */ + {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D27/PB0 */ + {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, + /* D28/PB1 */ + {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, + /* D29/PB10 */ + {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D30/PB11 */ + {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D31/PB12 */ + {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D32/PB13 */ + {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D33/PB14 */ + {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D34/PB15 */ + {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D35/PC6 */ + {GPIOC, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D36/PC7 */ + {GPIOC, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D37/PC8 */ + {GPIOC, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D38/PC9 (BUT) */ + {GPIOC, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC} +}; + +#elif defined(BOARD_maple_native) + +PinMapping PIN_MAP[NR_GPIO_PINS] = { + /* Top header */ + + /* D0/PB10 */ + {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D1/PB2 */ + {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D2/PB12 */ + {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D3/PB13 */ + {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D4/PB14 */ + {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D5/PB15 */ + {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D6/PC0 */ + {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D7/PC1 */ + {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D8/PC2 */ + {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D9/PC3 */ + {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D10/PC4 */ + {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D11/PC5 */ + {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D12/PC6 */ + {GPIOC, 6, ADCx, TIMER8_CH1_CCR, TIMER8, 1, AFIO_EXTI_PC}, + /* D13/PC7 */ + {GPIOC, 7, ADCx, TIMER8_CH2_CCR, TIMER8, 2, AFIO_EXTI_PC}, + /* D14/PC8 */ + {GPIOC, 8, ADCx, TIMER8_CH3_CCR, TIMER8, 3, AFIO_EXTI_PC}, + /* D15/PC9 */ + {GPIOC, 9, ADCx, TIMER8_CH4_CCR, TIMER8, 4, AFIO_EXTI_PC}, + /* D16/PC10 */ + {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D17/PC11 */ + {GPIOC, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D18/PC12 */ + {GPIOC, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D19/PC13 */ + {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D20/PC14 */ + {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D21/PC15 */ + {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D22/PA8 */ + {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, + /* D23/PA9 */ + {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, + /* D24/PA10 */ + {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, + /* D25/PB9 */ + {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, + + /* Bottom header */ + + /* D26/PD2 */ + {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D27/PD3 */ + {GPIOD, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D28/PD6 */ + {GPIOD, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D29/PG11 */ + {GPIOG, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D30/PG12 */ + {GPIOG, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D31/PG13 */ + {GPIOG, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D32/PG14 */ + {GPIOG, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D33/PG8 */ + {GPIOG, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D34/PG7 */ + {GPIOG, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D35/PG6 */ + {GPIOG, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D36/PB5 */ + {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D37/PB6 */ + {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, + /* D38/PB7 */ + {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, + /* D39/PF6 */ + {GPIOF, 6, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D40/PF7 */ + {GPIOF, 7, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D41/PF8 */ + {GPIOF, 8, 6, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D42/PF9 */ + {GPIOF, 9, 7, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D43/PF10 */ + {GPIOF, 10, 8, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D44/PF11 */ + {GPIOF, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D45/PB1 */ + {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, + /* D46/PB0 */ + {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, + /* D47/PA0 */ + {GPIOA, 0, 0, TIMER5_CH1_CCR, TIMER5, 1, AFIO_EXTI_PA}, + /* D48/PA1 */ /* FIXME (?) + What about D48--D50 also being TIMER2_CH[234]? */ + {GPIOA, 1, 1, TIMER5_CH2_CCR, TIMER5, 2, AFIO_EXTI_PA}, + /* D49/PA2 */ + {GPIOA, 2, 2, TIMER5_CH3_CCR, TIMER5, 3, AFIO_EXTI_PA}, + /* D50/PA3 */ + {GPIOA, 3, 3, TIMER5_CH4_CCR, TIMER5, 4, AFIO_EXTI_PA}, + /* D51/PA4 */ + {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D52/PA5 */ + {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D53/PA6 */ + {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, + /* D54/PA7 */ + {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, + + /* Right (triple) header */ + + /* D55/PF0 */ + {GPIOF, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D56/PD11 */ + {GPIOD, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D57/PD14 */ + {GPIOD, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D58/PF1 */ + {GPIOF, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D59/PD12 */ + {GPIOD, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D60/PD15 */ + {GPIOD, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D61/PF2 */ + {GPIOF, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D62/PD13 */ + {GPIOD, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D63/PD0 */ + {GPIOD, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D64/PF3 */ + {GPIOF, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D65/PE3 */ + {GPIOE, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D66/PD1 */ + {GPIOD, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D67/PF4 */ + {GPIOF, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D68/PE4 */ + {GPIOE, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D69/PE7 */ + {GPIOE, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D70/PF5 */ + {GPIOF, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D71/PE5 */ + {GPIOE, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D72/PE8 */ + {GPIOE, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D73/PF12 */ + {GPIOF, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D74/PE6 */ + {GPIOE, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D75/PE9 */ + {GPIOE, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D76/PF13 */ + {GPIOF, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D77/PE10 */ + {GPIOE, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D78/PF14 */ + {GPIOF, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D79/PG9 */ + {GPIOG, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D80/PE11 */ + {GPIOE, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D81/PF15 */ + {GPIOF, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, + /* D82/PG10 */ + {GPIOG, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D83/PE12 */ + {GPIOE, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D84/PG0 */ + {GPIOG, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D85/PD5 */ + {GPIOD, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D86/PE13 */ + {GPIOE, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D87/PG1 */ + {GPIOG, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D88/PD4 */ + {GPIOD, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D89/PE14 */ + {GPIOE, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D90/PG2 */ + {GPIOG, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D91/PE1 */ + {GPIOE, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D92/PE15 */ + {GPIOE, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D93/PG3 */ + {GPIOG, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D94/PE0 */ + {GPIOE, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, + /* D95/PD8 */ + {GPIOD, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D96/PG4 */ + {GPIOG, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D97/PD9 */ + {GPIOD, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D98/PG5 */ + {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, + /* D99/PD10 */ + {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD} +}; + +#elif defined(BOARD_maple_mini) + +PinMapping PIN_MAP[NR_GPIO_PINS] = { + /* D0/PB11 */ + {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D1/PB10 */ + {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D2/PB2 */ + {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D3/PB0 */ + {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, + /* D4/PA7 */ + {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, + /* D5/PA6 */ + {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, + /* D6/PA5 */ + {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D7/PA4 */ + {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D8/PA3 */ + {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, + /* D9/PA2 */ + {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, + /* D10/PA1 */ + {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, + /* D11/PA0 */ + {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, + /* D12/PC15 */ + {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D13/PC14 */ + {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D14/PC13 */ + {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D15/PB7 */ + {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, + /* D16/PB6 */ + {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, + /* D17/PB5 */ + {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D18/PB4 */ + {GPIOB, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D19/PB3 */ + {GPIOB, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D20/PA15 */ + {GPIOA, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D21/PA14 */ + {GPIOA, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D22/PA13 */ + {GPIOA, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D23/PA12 */ + {GPIOA, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D24/PA11 */ + {GPIOA, 11, ADCx, TIMER1_CH4_CCR, TIMER1, 4, AFIO_EXTI_PA}, + /* D25/PA10 */ + {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, + /* D26/PA9 */ + {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, + /* D27/PA8 */ + {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, + /* D28/PB15 */ + {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D29/PB14 */ + {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D30/PB13 */ + {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D31/PB12 */ + {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D32/PB8 */ + {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, + /* D33/PB1 */ + {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, +}; + +#else + +#error "Board type has not been selected correctly." + +#endif diff --git a/wirish/boards.h b/wirish/boards.h index ee93c5a..2941127 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -34,13 +34,11 @@ #include "libmaple.h" #include "gpio.h" #include "timers.h" -#include "exti.h" -#ifdef __cplusplus -extern "C" { -#endif - -/* Set of all possible digital pin names; not all boards have all these */ +/* Set of all possible pin names; not all boards have all these (note + that we use the Dx convention since all of the Maple's pins are + "digital" pins (e.g. can be used with digitalRead() and + digitalWrite()), but not all of them are connected to ADCs. */ enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, D10, D11, D12, D13, D14, D15, D16, D17, D18, D19, D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, @@ -53,17 +51,20 @@ enum { #define ADC_INVALID 0xFFFFFFFF -/* Types used for the tables below */ +/* Pin mapping: pin number -> STM32 info */ typedef struct PinMapping { - GPIO_Port *port; + gpio_dev *gpio_device; uint32 pin; uint32 adc_channel; TimerCCR timer_ccr; - uint32 exti_port; timer_dev_num timer_num; uint32 timer_chan; + afio_exti_port ext_port; } PinMapping; +/* Maps every digital pin to a PinMapping */ +extern PinMapping PIN_MAP[]; + /* LeafLabs Maple rev3, rev5 */ #ifdef BOARD_maple @@ -77,93 +78,6 @@ typedef struct PinMapping { intended for general use. */ #define NR_GPIO_PINS 39 - static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* D0/PA3 */ - {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, - /* D1/PA2 */ - {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, - /* D2/PA0 */ - {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, - /* D3/PA1 */ - {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, - /* D4/PB5 */ - {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D5/PB6 */ - {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, - /* D6/PA8 */ - {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, - /* D7/PA9 */ - {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, - /* D8/PA10 */ - {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, - /* D9/PB7 */ - {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, - /* D10/PA4 */ - {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D11/PA7 */ - {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, - /* D12/PA6 */ - {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, - /* D13/PA5 */ - {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D14/PB8 */ - {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3}, - - /* Little header */ - - /* D15/PC0 */ - {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D16/PC1 */ - {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D17/PC2 */ - {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D18/PC3 */ - {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D19/PC4 */ - {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D20/PC5 */ - {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - - /* External header */ - - /* D21/PC13 */ - {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D22/PC14 */ - {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D23/PC15 */ - {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D24/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, - /* D25/PD2 */ - {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D26/PC10 */ - {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D27/PB0 */ - {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, - /* D28/PB1 */ - {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, - /* D29/PB10 */ - {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D30/PB11 */ - {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D31/PB12 */ - {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D32/PB13 */ - {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D33/PB14 */ - {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D34/PB15 */ - {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D35/PC6 */ - {GPIOC_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D36/PC7 */ - {GPIOC_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D37/PC8 */ - {GPIOC_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D38/PC9 (BUT) */ - {GPIOC_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID} - }; - #define BOARD_INIT do { \ } while(0) @@ -179,218 +93,6 @@ typedef struct PinMapping { #define NR_GPIO_PINS 100 - static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* Top header */ - - /* D0/PB10 */ - {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D1/PB2 */ - {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D2/PB12 */ - {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D3/PB13 */ - {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D4/PB14 */ - {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D5/PB15 */ - {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D6/PC0 */ - {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D7/PC1 */ - {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D8/PC2 */ - {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D9/PC3 */ - {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D10/PC4 */ - {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D11/PC5 */ - {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D12/PC6 */ - {GPIOC_BASE, 6, ADC_INVALID, TIMER8_CH1_CCR, EXTI_CONFIG_PORTC, TIMER8, 1}, - /* D13/PC7 */ - {GPIOC_BASE, 7, ADC_INVALID, TIMER8_CH2_CCR, EXTI_CONFIG_PORTC, TIMER8, 2}, - /* D14/PC8 */ - {GPIOC_BASE, 8, ADC_INVALID, TIMER8_CH3_CCR, EXTI_CONFIG_PORTC, TIMER8, 3}, - /* D15/PC9 */ - {GPIOC_BASE, 9, ADC_INVALID, TIMER8_CH4_CCR, EXTI_CONFIG_PORTC, TIMER8, 4}, - /* D16/PC10 */ - {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D17/PC11 */ - {GPIOC_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D18/PC12 */ - {GPIOC_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D19/PC13 */ - {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D20/PC14 */ - {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D21/PC15 */ - {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D22/PA8 */ - {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1}, - /* D23/PA9 */ - {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2}, - /* D24/PA10 */ - {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, - /* D25/PB9 */ - {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4}, - - /* Bottom header */ - - /* D26/PD2 */ - {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D27/PD3 */ - {GPIOD_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D28/PD6 */ - {GPIOD_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D29/PG11 */ - {GPIOG_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D30/PG12 */ - {GPIOG_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D31/PG13 */ - {GPIOG_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D32/PG14 */ - {GPIOG_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D33/PG8 */ - {GPIOG_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D34/PG7 */ - {GPIOG_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D35/PG6 */ - {GPIOG_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D36/PB5 */ - {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D37/PB6 */ - {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, - /* D38/PB7 */ - {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2}, - /* D39/PF6 */ - {GPIOF_BASE, 6, 4, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D40/PF7 */ - {GPIOF_BASE, 7, 5, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D41/PF8 */ - {GPIOF_BASE, 8, 6, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D42/PF9 */ - {GPIOF_BASE, 9, 7, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D43/PF10 */ - {GPIOF_BASE, 10, 8, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D44/PF11 */ - {GPIOF_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D45/PB1 */ - {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, - /* D46/PB0 */ - {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, - /* D47/PA0 */ - {GPIOA_BASE, 0, 0, TIMER5_CH1_CCR, EXTI_CONFIG_PORTA, TIMER5, 1}, - /* D48/PA1 */ - {GPIOA_BASE, 1, 1, TIMER5_CH2_CCR, EXTI_CONFIG_PORTA, TIMER5, 2}, /* FIXME (?) what to do about D48--D50 - also being TIMER2_CH[2,3,4]? */ - /* D49/PA2 */ - {GPIOA_BASE, 2, 2, TIMER5_CH3_CCR, EXTI_CONFIG_PORTA, TIMER5, 3}, - /* D50/PA3 */ - {GPIOA_BASE, 3, 3, TIMER5_CH4_CCR, EXTI_CONFIG_PORTA, TIMER5, 4}, - /* D51/PA4 */ - {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D52/PA5 */ - {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D53/PA6 */ - {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, - /* D54/PA7 */ - {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, - - /* Right (triple) header */ - - /* D55/PF0 */ - {GPIOF_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D56/PD11 */ - {GPIOD_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D57/PD14 */ - {GPIOD_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D58/PF1 */ - {GPIOF_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D59/PD12 */ - {GPIOD_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D60/PD15 */ - {GPIOD_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D61/PF2 */ - {GPIOF_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D62/PD13 */ - {GPIOD_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D63/PD0 */ - {GPIOD_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D64/PF3 */ - {GPIOF_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D65/PE3 */ - {GPIOE_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D66/PD1 */ - {GPIOD_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D67/PF4 */ - {GPIOF_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D68/PE4 */ - {GPIOE_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D69/PE7 */ - {GPIOE_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D70/PF5 */ - {GPIOF_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D71/PE5 */ - {GPIOE_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D72/PE8 */ - {GPIOE_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D73/PF12 */ - {GPIOF_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D74/PE6 */ - {GPIOE_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D75/PE9 */ - {GPIOE_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D76/PF13 */ - {GPIOF_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D77/PE10 */ - {GPIOE_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D78/PF14 */ - {GPIOF_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D79/PG9 */ - {GPIOG_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D80/PE11 */ - {GPIOE_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D81/PF15 */ - {GPIOF_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID}, - /* D82/PG10 */ - {GPIOG_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D83/PE12 */ - {GPIOE_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D84/PG0 */ - {GPIOG_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D85/PD5 */ - {GPIOD_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D86/PE13 */ - {GPIOE_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D87/PG1 */ - {GPIOG_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D88/PD4 */ - {GPIOD_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D89/PE14 */ - {GPIOE_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D90/PG2 */ - {GPIOG_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D91/PE1 */ - {GPIOE_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D92/PE15 */ - {GPIOE_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D93/PG3 */ - {GPIOG_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D94/PE0 */ - {GPIOE_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID}, - /* D95/PD8 */ - {GPIOD_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D96/PG4 */ - {GPIOG_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D97/PD9 */ - {GPIOD_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}, - /* D98/PG5 */ - {GPIOG_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID}, - /* D99/PD10 */ - {GPIOD_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID} - }; - #define BOARD_INIT do { \ } while(0) @@ -404,83 +106,11 @@ typedef struct PinMapping { #define NR_GPIO_PINS 34 - static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* D0/PB11 */ - {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D1/PB10 */ - {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D2/PB2 */ - {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D3/PB0 */ - {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3}, - /* D4/PA7 */ - {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2}, - /* D5/PA6 */ - {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1}, - /* D6/PA5 */ - {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D7/PA4 */ - {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D8/PA3 */ - {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4}, - /* D9/PA2 */ - {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3}, - /* D10/PA1 */ - {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, - /* D11/PA0 */ - {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1}, - /* D12/PC15 */ - {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D13/PC14 */ - {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D14/PC13 */ - {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}, - /* D15/PB7 */ - {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, - /* D16/PB6 */ - {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1}, - /* D17/PB5 */ - {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D18/PB4 */ - {GPIOB_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D19/PB3 */ - {GPIOB_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D20/PA15 */ - {GPIOA_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D21/PA14 */ - {GPIOA_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D22/PA13 */ - {GPIOA_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D23/PA12 */ - {GPIOA_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID}, - /* D24/PA11 */ - {GPIOA_BASE, 11, ADC_INVALID, TIMER1_CH4_CCR, EXTI_CONFIG_PORTA, TIMER1, 4}, - /* D25/PA10 */ - {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3}, - /* D26/PA9 */ - {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2}, - /* D27/PA8 */ - {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTB, TIMER1, 1}, - /* D28/PB15 */ - {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D29/PB14 */ - {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D30/PB13 */ - {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D31/PB12 */ - {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID}, - /* D32/PB8 */ - {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3}, - /* D33/PB1 */ - {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4}, - }; - - /* since we want the Serial Wire/JTAG pins as GPIOs, disable both - SW and JTAG debug support */ - /* don't use __clear_bits here! */ + /* Since we want the Serial Wire/JTAG pins as GPIOs, disable both + * SW and JTAG debug support */ #define BOARD_INIT \ do { \ - *AFIO_MAPR = (*AFIO_MAPR | BIT(26)) & ~(BIT(25) | BIT(24)); \ + afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); \ } while (0) #else @@ -489,9 +119,4 @@ typedef struct PinMapping { #endif -#ifdef __cplusplus -} // extern "C" -#endif - #endif - diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp index d6c7e82..08252d8 100644 --- a/wirish/comm/HardwareSerial.cpp +++ b/wirish/comm/HardwareSerial.cpp @@ -34,21 +34,21 @@ #include "gpio.h" #include "timers.h" -HardwareSerial Serial1(USART1, 4500000UL, GPIOA_BASE, 9,10, TIMER1, 2); -HardwareSerial Serial2(USART2, 2250000UL, GPIOA_BASE, 2, 3, TIMER2, 3); -HardwareSerial Serial3(USART3, 2250000UL, GPIOB_BASE, 10,11, TIMER_INVALID, 0); +HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9,10, TIMER1, 2); +HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3); +HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10,11, TIMER_INVALID, 0); // TODO: High density device ports HardwareSerial::HardwareSerial(uint8 usart_num, uint32 max_baud, - GPIO_Port *gpio_port, + gpio_dev *gpio_device, uint8 tx_pin, uint8 rx_pin, timer_dev_num timer_num, uint8 compare_num) { this->usart_num = usart_num; this->max_baud = max_baud; - this->gpio_port = gpio_port; + this->gpio_device = gpio_device; this->tx_pin = tx_pin; this->rx_pin = rx_pin; this->timer_num = timer_num; @@ -72,8 +72,8 @@ void HardwareSerial::begin(uint32 baud) { return; } - gpio_set_mode(gpio_port, tx_pin, GPIO_MODE_AF_OUTPUT_PP); - gpio_set_mode(gpio_port, rx_pin, GPIO_MODE_INPUT_FLOATING); + gpio_set_mode(gpio_device, tx_pin, GPIO_AF_OUTPUT_PP); + gpio_set_mode(gpio_device, rx_pin, GPIO_INPUT_FLOATING); if (timer_num != TIMER_INVALID) { /* turn off any pwm if there's a conflict on this usart */ diff --git a/wirish/comm/HardwareSerial.h b/wirish/comm/HardwareSerial.h index aad8aa7..ef19a56 100644 --- a/wirish/comm/HardwareSerial.h +++ b/wirish/comm/HardwareSerial.h @@ -46,7 +46,7 @@ class HardwareSerial : public Print { private: uint8 usart_num; uint32 max_baud; - GPIO_Port *gpio_port; + gpio_dev *gpio_device; uint8 tx_pin; uint8 rx_pin; timer_dev_num timer_num; @@ -54,7 +54,7 @@ class HardwareSerial : public Print { public: HardwareSerial(uint8 usart_num, uint32 max_baud, - GPIO_Port *gpio_port, + gpio_dev *gpio_device, uint8 tx_pin, uint8 rx_pin, timer_dev_num timer_num, diff --git a/wirish/ext_interrupts.c b/wirish/ext_interrupts.c deleted file mode 100644 index dd7c1a8..0000000 --- a/wirish/ext_interrupts.c +++ /dev/null @@ -1,79 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @file ext_interrupts.c - * - * @brief Wiring-like interface for external interrupts - */ - -#include "wirish.h" -#include "exti.h" -#include "ext_interrupts.h" - -/* Attach ISR handler on pin, triggering on the given mode. */ -void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { - uint8 outMode; - - /* Parameter checking */ - if (pin >= NR_GPIO_PINS) { - return; - } - - if (!handler) { - return; - } - - switch (mode) { - case RISING: - outMode = EXTI_RISING; - break; - case FALLING: - outMode = EXTI_FALLING; - break; - case CHANGE: - outMode = EXTI_RISING_FALLING; - break; - default: - ASSERT(0); - return; - } - - exti_attach_interrupt(PIN_MAP[pin].exti_port, - PIN_MAP[pin].pin, - handler, - mode); - - return; -} - -/* Disable any interrupts */ -void detachInterrupt(uint8 pin) { - if (!(pin < NR_GPIO_PINS)) { - return; - } - - exti_detach_interrupt(PIN_MAP[pin].pin); -} - diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp new file mode 100644 index 0000000..5b32b05 --- /dev/null +++ b/wirish/ext_interrupts.cpp @@ -0,0 +1,82 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @file ext_interrupts.c + * + * @brief Wiring-like interface for external interrupts + */ + +#include "boards.h" +#include "gpio.h" +#include "exti.h" +#include "ext_interrupts.h" + +static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode); + +/** + * @brief Attach an interrupt handler to a pin, triggering on the given mode. + * @param pin Pin to attach an interrupt handler onto. + * @param handler Function to call when the external interrupt is triggered. + * @param mode Trigger mode for the given interrupt. + * @see ExtIntTriggerMode + */ +void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { + if (pin >= NR_GPIO_PINS || !handler) { + return; + } + + exti_trigger_mode outMode = exti_out_mode(mode); + + exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].pin), + PIN_MAP[pin].ext_port, + handler, + outMode); +} + +/** + * @brief Disable any external interrupt attached to a pin. + * @param pin Pin number to detach any interrupt from. + */ +void detachInterrupt(uint8 pin) { + if (pin >= NR_GPIO_PINS) { + return; + } + + exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].pin)); +} + +static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) { + switch (mode) { + case RISING: + return EXTI_RISING; + case FALLING: + return EXTI_FALLING; + case CHANGE: + return EXTI_RISING_FALLING; + } + // Can't happen + ASSERT(0); + return (exti_trigger_mode)0; +} diff --git a/wirish/ext_interrupts.h b/wirish/ext_interrupts.h index 4e22c71..364bcda 100644 --- a/wirish/ext_interrupts.h +++ b/wirish/ext_interrupts.h @@ -28,7 +28,7 @@ /** * @file ext_interrupts.h * - * @brief External interrupt wiring prototypes and types + * @brief Wiring-like external interrupt prototypes and types. */ #ifndef _EXT_INTERRUPTS_H_ @@ -48,10 +48,6 @@ typedef enum ExtIntTriggerMode_ { changes). */ } ExtIntTriggerMode; -#ifdef __cplusplus -extern "C"{ -#endif - /** * @brief Registers an interrupt handler on a pin. * @@ -104,10 +100,5 @@ static inline void noInterrupts() { nvic_globalirq_disable(); } -#ifdef __cplusplus -} -#endif - - #endif diff --git a/wirish/io.h b/wirish/io.h index 2d22dcd..d2e4d2d 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -35,10 +35,6 @@ #include "adc.h" #include "time.h" -#ifdef __cplusplus -extern "C"{ -#endif - /** * Specifies a GPIO pin behavior. * @@ -68,11 +64,11 @@ typedef enum WiringPinMode { supply through a large resistor). When the pin is high, not much current flows through to ground and the line stays at positive - voltage; when the pin is low the bus + voltage; when the pin is low, the bus "drains" to ground with a small amount of current constantly flowing through the large resistor from the external supply. In this - mode no current is ever actually /sourced/ + mode, no current is ever actually sourced from the pin. */ INPUT, /**< Basic digital input. The pin voltage is sampled; when @@ -220,8 +216,5 @@ uint8 isButtonPressed(); */ uint8 waitForButtonPress(uint32 timeout_millis); -#ifdef __cplusplus -} // extern "C" -#endif #endif diff --git a/wirish/pwm.c b/wirish/pwm.c deleted file mode 100644 index 072e4cd..0000000 --- a/wirish/pwm.c +++ /dev/null @@ -1,48 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief Arduino-compatible PWM implementation. - */ - -#include "wirish.h" -#include "timers.h" -#include "io.h" -#include "pwm.h" - -void pwmWrite(uint8 pin, uint16 duty_cycle) { - TimerCCR ccr; - - if (pin >= NR_GPIO_PINS) { - return; - } - - ccr = PIN_MAP[pin].timer_ccr; - - if (ccr == 0) { - return; - } - - timer_pwm_write_ccr(ccr, duty_cycle); -} diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp new file mode 100644 index 0000000..072e4cd --- /dev/null +++ b/wirish/pwm.cpp @@ -0,0 +1,48 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief Arduino-compatible PWM implementation. + */ + +#include "wirish.h" +#include "timers.h" +#include "io.h" +#include "pwm.h" + +void pwmWrite(uint8 pin, uint16 duty_cycle) { + TimerCCR ccr; + + if (pin >= NR_GPIO_PINS) { + return; + } + + ccr = PIN_MAP[pin].timer_ccr; + + if (ccr == 0) { + return; + } + + timer_pwm_write_ccr(ccr, duty_cycle); +} diff --git a/wirish/pwm.h b/wirish/pwm.h index d0bc9e0..a6385e9 100644 --- a/wirish/pwm.h +++ b/wirish/pwm.h @@ -28,12 +28,8 @@ * @brief Arduino-compatible PWM interface. */ -#ifndef _PWM_H -#define _PWM_H - -#ifdef __cplusplus -extern "C"{ -#endif +#ifndef _PWM_H_ +#define _PWM_H_ /** * As a convenience, analogWrite is an alias of pwmWrite to ease @@ -50,10 +46,5 @@ extern "C"{ */ void pwmWrite(uint8 pin, uint16 duty_cycle); -#ifdef __cplusplus -} -#endif - - #endif diff --git a/wirish/rules.mk b/wirish/rules.mk index cb5a69f..cea34f5 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -11,21 +11,23 @@ WIRISH_INCLUDES := -I$(d) -I$(d)/comm CFLAGS_$(d) := $(WIRISH_INCLUDES) $(LIBMAPLE_INCLUDES) # Local rules and targets -cSRCS_$(d) := wirish.c \ - wirish_shift.c \ - wirish_analog.c \ - time.c \ - pwm.c \ - ext_interrupts.c \ - wirish_digital.c - -cppSRCS_$(d) := wirish_math.cpp \ - Print.cpp \ - comm/HardwareSerial.cpp \ - comm/HardwareSPI.cpp \ - usb_serial.cpp \ - HardwareTimer.cpp \ - cxxabi-compat.cpp \ +cSRCS_$(d) := + +cppSRCS_$(d) := wirish_math.cpp \ + Print.cpp \ + comm/HardwareSerial.cpp \ + comm/HardwareSPI.cpp \ + usb_serial.cpp \ + HardwareTimer.cpp \ + cxxabi-compat.cpp \ + wirish.cpp \ + wirish_shift.cpp \ + wirish_analog.cpp \ + time.cpp \ + pwm.cpp \ + ext_interrupts.cpp \ + wirish_digital.cpp \ + boards.cpp cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%) diff --git a/wirish/time.c b/wirish/time.c deleted file mode 100644 index c0a0649..0000000 --- a/wirish/time.c +++ /dev/null @@ -1,52 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief Delay implementation. - */ - -#include "libmaple.h" -#include "systick.h" -#include "time.h" - -void delay(unsigned long ms) { - uint32 i; - for (i = 0; i < ms; i++) { - delayMicroseconds(1000); - } -} - -void delayMicroseconds(uint32 us) { - /* So (2^32)/12 micros max, or less than 6 minutes */ - us *= 12; - - /* fudge for function call overhead */ - us--; - asm volatile(" mov r0, %[us] \n\t" - "1: subs r0, #1 \n\t" - " bhi 1b \n\t" - : - : [us] "r" (us) - : "r0"); -} diff --git a/wirish/time.cpp b/wirish/time.cpp new file mode 100644 index 0000000..c0a0649 --- /dev/null +++ b/wirish/time.cpp @@ -0,0 +1,52 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief Delay implementation. + */ + +#include "libmaple.h" +#include "systick.h" +#include "time.h" + +void delay(unsigned long ms) { + uint32 i; + for (i = 0; i < ms; i++) { + delayMicroseconds(1000); + } +} + +void delayMicroseconds(uint32 us) { + /* So (2^32)/12 micros max, or less than 6 minutes */ + us *= 12; + + /* fudge for function call overhead */ + us--; + asm volatile(" mov r0, %[us] \n\t" + "1: subs r0, #1 \n\t" + " bhi 1b \n\t" + : + : [us] "r" (us) + : "r0"); +} diff --git a/wirish/time.h b/wirish/time.h index 8d3d074..a0c0c82 100644 --- a/wirish/time.h +++ b/wirish/time.h @@ -35,10 +35,6 @@ #include "systick.h" #include "boards.h" -#ifdef __cplusplus -extern "C"{ -#endif - #define US_PER_MS 1000 /** @@ -99,10 +95,5 @@ void delay(unsigned long ms); */ void delayMicroseconds(uint32 us); -#ifdef __cplusplus -} // extern "C" -#endif - - #endif diff --git a/wirish/wirish.c b/wirish/wirish.c deleted file mode 100644 index 4c84d26..0000000 --- a/wirish/wirish.c +++ /dev/null @@ -1,81 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief generic maple board bring up: - * - * By default, we bring up all maple boards running on the stm32 to 72mhz, - * clocked off the PLL, driven by the 8MHz external crystal. - * - * AHB and APB2 are clocked at 72MHz - * APB1 is clocked at 36MHz - */ - -#include "wirish.h" -#include "systick.h" -#include "gpio.h" -#include "nvic.h" -#include "usb.h" -#include "rcc.h" -#include "fsmc.h" -#include "dac.h" -#include "flash.h" - -void init(void) { - /* make sure the flash is ready before spinning the high speed clock up */ - flash_enable_prefetch(); - flash_set_latency(FLASH_WAIT_STATE_2); - -#ifdef STM32_HIGH_DENSITY - fsmc_native_sram_init(); -#endif - - /* initialize clocks */ - rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); - rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); - rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); - rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); - - nvic_init(); - systick_init(SYSTICK_RELOAD_VAL); - gpio_init(); - - /* Initialize the ADC for slow conversions, to allow for high - impedance inputs. */ - adc_init(ADC1, 0); - adc_set_sample_rate(ADC1, ADC_SMPR_55_5); - - timer_init(TIMER1, 1); - timer_init(TIMER2, 1); - timer_init(TIMER3, 1); - timer_init(TIMER4, 1); -#ifdef STM32_HIGH_DENSITY - timer_init(TIMER5, 1); - timer_init(TIMER8, 1); -#endif - setupUSB(); - - /* include the board-specific init macro */ - BOARD_INIT; -} diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp new file mode 100644 index 0000000..01f4507 --- /dev/null +++ b/wirish/wirish.cpp @@ -0,0 +1,82 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief generic maple board bring up: + * + * By default, we bring up all maple boards running on the stm32 to 72mhz, + * clocked off the PLL, driven by the 8MHz external crystal. + * + * AHB and APB2 are clocked at 72MHz + * APB1 is clocked at 36MHz + */ + +#include "wirish.h" +#include "systick.h" +#include "gpio.h" +#include "nvic.h" +#include "usb.h" +#include "rcc.h" +#include "fsmc.h" +#include "dac.h" +#include "flash.h" + +void init(void) { + /* make sure the flash is ready before spinning the high speed clock up */ + flash_enable_prefetch(); + flash_set_latency(FLASH_WAIT_STATE_2); + +#ifdef STM32_HIGH_DENSITY + fsmc_native_sram_init(); +#endif + + /* initialize clocks */ + rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); + rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); + rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); + rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); + + nvic_init(); + systick_init(SYSTICK_RELOAD_VAL); + gpio_init_all(); + afio_init(); + + /* Initialize the ADC for slow conversions, to allow for high + impedance inputs. */ + adc_init(ADC1, 0); + adc_set_sample_rate(ADC1, ADC_SMPR_55_5); + + timer_init(TIMER1, 1); + timer_init(TIMER2, 1); + timer_init(TIMER3, 1); + timer_init(TIMER4, 1); +#ifdef STM32_HIGH_DENSITY + timer_init(TIMER5, 1); + timer_init(TIMER8, 1); +#endif + // setupUSB(); + + /* include the board-specific init macro */ + BOARD_INIT; +} diff --git a/wirish/wirish.h b/wirish/wirish.h index 311c74f..447b2b6 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -32,25 +32,19 @@ #define _WIRISH_H_ #include "libmaple.h" -#include "boards.h" -#include "time.h" #include "timers.h" + +#include "boards.h" #include "io.h" #include "bits.h" #include "pwm.h" #include "ext_interrupts.h" #include "wirish_math.h" - -#ifdef __cplusplus +#include "time.h" #include "HardwareSPI.h" #include "HardwareSerial.h" #include "usb_serial.h" #include "HardwareTimer.h" -#endif - -#ifdef __cplusplus -extern "C"{ -#endif /* Arduino wiring macros and bit defines */ #define HIGH 0x1 @@ -77,9 +71,5 @@ typedef uint8 byte; void init(void); void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, byte val); -#ifdef __cplusplus -} // extern "C" -#endif - #endif diff --git a/wirish/wirish_analog.c b/wirish/wirish_analog.c deleted file mode 100644 index a658184..0000000 --- a/wirish/wirish_analog.c +++ /dev/null @@ -1,41 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief Arduino-compatible ADC implementation. - */ - -#include "libmaple.h" -#include "wirish.h" -#include "io.h" - -/* Assumes that the ADC has been initialized and that the pin is set - * to ANALOG_INPUT */ -uint32 analogRead(uint8 pin) { - if(PIN_MAP[pin].adc_channel == ADC_INVALID) { - return 0; - } - - return adc_read(ADC1, PIN_MAP[pin].adc_channel); -} diff --git a/wirish/wirish_analog.cpp b/wirish/wirish_analog.cpp new file mode 100644 index 0000000..a658184 --- /dev/null +++ b/wirish/wirish_analog.cpp @@ -0,0 +1,41 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief Arduino-compatible ADC implementation. + */ + +#include "libmaple.h" +#include "wirish.h" +#include "io.h" + +/* Assumes that the ADC has been initialized and that the pin is set + * to ANALOG_INPUT */ +uint32 analogRead(uint8 pin) { + if(PIN_MAP[pin].adc_channel == ADC_INVALID) { + return 0; + } + + return adc_read(ADC1, PIN_MAP[pin].adc_channel); +} diff --git a/wirish/wirish_digital.c b/wirish/wirish_digital.c deleted file mode 100644 index bb28f0a..0000000 --- a/wirish/wirish_digital.c +++ /dev/null @@ -1,142 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/* - * Arduino-compatible digital I/O implementation. - */ - -#include "wirish.h" -#include "io.h" - -void pinMode(uint8 pin, WiringPinMode mode) { - uint8 outputMode; - boolean pwm = false; - - if (pin >= NR_GPIO_PINS) { - return; - } - - switch(mode) { - case OUTPUT: - outputMode = GPIO_MODE_OUTPUT_PP; - break; - case OUTPUT_OPEN_DRAIN: - outputMode = GPIO_MODE_OUTPUT_OD; - break; - case INPUT: - case INPUT_FLOATING: - outputMode = GPIO_MODE_INPUT_FLOATING; - break; - case INPUT_ANALOG: - outputMode = GPIO_MODE_INPUT_ANALOG; - break; - case INPUT_PULLUP: - outputMode = GPIO_MODE_INPUT_PU; - break; - case INPUT_PULLDOWN: - outputMode = GPIO_MODE_INPUT_PD; - break; - case PWM: - outputMode = GPIO_MODE_AF_OUTPUT_PP; - pwm = true; - break; - case PWM_OPEN_DRAIN: - outputMode = GPIO_MODE_AF_OUTPUT_OD; - pwm = true; - break; - default: - ASSERT(0); - return; - } - - gpio_set_mode(PIN_MAP[pin].port, PIN_MAP[pin].pin, outputMode); - - if (PIN_MAP[pin].timer_num != TIMER_INVALID) { - /* enable/disable timer channels if we're switching into or - out of pwm */ - if (pwm) { - timer_set_mode(PIN_MAP[pin].timer_num, - PIN_MAP[pin].timer_chan, - TIMER_PWM); - } else { - timer_set_mode(PIN_MAP[pin].timer_num, - PIN_MAP[pin].timer_chan, - TIMER_DISABLED); - } - } -} - - -uint32 digitalRead(uint8 pin) { - if (pin >= NR_GPIO_PINS) { - return 0; - } - - return gpio_read_bit(PIN_MAP[pin].port, PIN_MAP[pin].pin); -} - -void digitalWrite(uint8 pin, uint8 val) { - if (pin >= NR_GPIO_PINS) { - return; - } - - gpio_write_bit(PIN_MAP[pin].port, PIN_MAP[pin].pin, val); -} - -void togglePin(uint8 pin) { - if (pin >= NR_GPIO_PINS) { - return; - } - - gpio_toggle_pin(PIN_MAP[pin].port, PIN_MAP[pin].pin); -} - -uint8 isButtonPressed() { - if (digitalRead(BOARD_BUTTON_PIN)) { - delay(1); - while (digitalRead(BOARD_BUTTON_PIN)) - ; - return true; - } - return false; -} - -uint8 waitForButtonPress(uint32 timeout) { - uint32 start = millis(); - uint32 time; - if (timeout == 0) { - while (!isButtonPressed()) - ; - return true; - } - do { - time = millis(); - /* properly handle wrap-around */ - if ((start > time && time + (0xffffffffU - start) > timeout) || - time - start > timeout) { - return false; - } - } while (!isButtonPressed()); - return true; -} diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp new file mode 100644 index 0000000..0c0bd85 --- /dev/null +++ b/wirish/wirish_digital.cpp @@ -0,0 +1,143 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/* + * Arduino-compatible digital I/O implementation. + */ + +#include "wirish.h" +#include "io.h" + +void pinMode(uint8 pin, WiringPinMode mode) { + gpio_pin_mode outputMode; + boolean pwm = false; + + if (pin >= NR_GPIO_PINS) { + return; + } + + switch(mode) { + case OUTPUT: + outputMode = GPIO_OUTPUT_PP; + break; + case OUTPUT_OPEN_DRAIN: + outputMode = GPIO_OUTPUT_OD; + break; + case INPUT: + case INPUT_FLOATING: + outputMode = GPIO_INPUT_FLOATING; + break; + case INPUT_ANALOG: + outputMode = GPIO_INPUT_ANALOG; + break; + case INPUT_PULLUP: + outputMode = GPIO_INPUT_PU; + break; + case INPUT_PULLDOWN: + outputMode = GPIO_INPUT_PD; + break; + case PWM: + outputMode = GPIO_AF_OUTPUT_PP; + pwm = true; + break; + case PWM_OPEN_DRAIN: + outputMode = GPIO_AF_OUTPUT_OD; + pwm = true; + break; + default: + ASSERT(0); + return; + } + + gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, outputMode); + + if (PIN_MAP[pin].timer_num != TIMER_INVALID) { + /* enable/disable timer channels if we're switching into or + out of pwm */ + if (pwm) { + timer_set_mode(PIN_MAP[pin].timer_num, + PIN_MAP[pin].timer_chan, + TIMER_PWM); + } else { + timer_set_mode(PIN_MAP[pin].timer_num, + PIN_MAP[pin].timer_chan, + TIMER_DISABLED); + } + } +} + + +uint32 digitalRead(uint8 pin) { + if (pin >= NR_GPIO_PINS) { + return 0; + } + + return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin) ? + HIGH : LOW; +} + +void digitalWrite(uint8 pin, uint8 val) { + if (pin >= NR_GPIO_PINS) { + return; + } + + gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, val); +} + +void togglePin(uint8 pin) { + if (pin >= NR_GPIO_PINS) { + return; + } + + gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin); +} + +uint8 isButtonPressed() { + if (digitalRead(BOARD_BUTTON_PIN)) { + delay(1); + while (digitalRead(BOARD_BUTTON_PIN)) + ; + return true; + } + return false; +} + +uint8 waitForButtonPress(uint32 timeout) { + uint32 start = millis(); + uint32 time; + if (timeout == 0) { + while (!isButtonPressed()) + ; + return true; + } + do { + time = millis(); + /* properly handle wrap-around */ + if ((start > time && time + (0xffffffffU - start) > timeout) || + time - start > timeout) { + return false; + } + } while (!isButtonPressed()); + return true; +} diff --git a/wirish/wirish_math.h b/wirish/wirish_math.h index 14614ba..fa544a9 100644 --- a/wirish/wirish_math.h +++ b/wirish/wirish_math.h @@ -24,7 +24,7 @@ /** * @file wirish_math.h - * @brief Includes cmath; provides Arduino-compatible math routines. + * @brief Includes ; provides Arduino-compatible math routines. */ #ifndef _WIRING_MATH_H_ @@ -32,8 +32,6 @@ #include -#ifdef __cplusplus - /** * @brief Initialize the pseudo-random number generator. * @param seed the number used to initialize the seed; cannot be zero. @@ -78,8 +76,7 @@ long random(long min, long max); * @param toEnd the end of the value's mapped range. * @return the mapped value. */ -/* TODO: profile code bloat due to inlining this */ -inline long map(long value, long fromStart, long fromEnd, +static inline long map(long value, long fromStart, long fromEnd, long toStart, long toEnd) { return (value - fromStart) * (toEnd - toStart) / (fromEnd - fromStart) + toStart; @@ -105,8 +102,6 @@ inline long map(long value, long fromStart, long fromEnd, #endif #define abs(x) (((x) > 0) ? (x) : -(unsigned)(x)) -#endif - /* Following are duplicate declarations (with Doxygen comments) for * some of the math.h functions; this is for the convenience of the * Sphinx docs. diff --git a/wirish/wirish_shift.c b/wirish/wirish_shift.c deleted file mode 100644 index f67364d..0000000 --- a/wirish/wirish_shift.c +++ /dev/null @@ -1,40 +0,0 @@ -/* - * wiring_shift.c - shiftOut() function - * Part of Arduino - http://www.arduino.cc/ - * - * Copyright (c) 2005-2006 David A. Mellis - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public License - * as published by the Free Software Foundation; either version 2.1 of - * the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 - * USA - * - * $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $ - */ - -#include "wirish.h" - -void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 val) { - int i; - - for (i = 0; i < 8; i++) { - if (bitOrder == LSBFIRST) { - digitalWrite(dataPin, !!(val & (1 << i))); - } else { - digitalWrite(dataPin, !!(val & (1 << (7 - i)))); - } - - digitalWrite(clockPin, HIGH); - digitalWrite(clockPin, LOW); - } -} diff --git a/wirish/wirish_shift.cpp b/wirish/wirish_shift.cpp new file mode 100644 index 0000000..f67364d --- /dev/null +++ b/wirish/wirish_shift.cpp @@ -0,0 +1,40 @@ +/* + * wiring_shift.c - shiftOut() function + * Part of Arduino - http://www.arduino.cc/ + * + * Copyright (c) 2005-2006 David A. Mellis + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public License + * as published by the Free Software Foundation; either version 2.1 of + * the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 + * USA + * + * $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $ + */ + +#include "wirish.h" + +void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 val) { + int i; + + for (i = 0; i < 8; i++) { + if (bitOrder == LSBFIRST) { + digitalWrite(dataPin, !!(val & (1 << i))); + } else { + digitalWrite(dataPin, !!(val & (1 << (7 - i)))); + } + + digitalWrite(clockPin, HIGH); + digitalWrite(clockPin, LOW); + } +} -- cgit v1.2.3 From f41c5d82be0e0cd06c82d2d6cfce2254327dd757 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 11 Mar 2011 16:37:05 -0500 Subject: Oops. --- wirish/wirish.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index 01f4507..f2fb89b 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -75,7 +75,7 @@ void init(void) { timer_init(TIMER5, 1); timer_init(TIMER8, 1); #endif - // setupUSB(); + setupUSB(); /* include the board-specific init macro */ BOARD_INIT; -- cgit v1.2.3 From 9579e9487c2039df38cc4fd0ac2846ef07cc0947 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 11 Mar 2011 20:43:59 -0500 Subject: shiftOut(), docs fixes --- docs/source/bootloader.rst | 56 ++++++------ docs/source/lang/api/constants.rst | 8 -- docs/source/lang/api/shiftout.rst | 99 ++++++++++++++++++++ docs/source/lang/unimplemented/shiftout.rst | 136 ---------------------------- docs/source/language-index.rst | 1 - docs/source/language.rst | 9 +- wirish/io.h | 16 ++++ 7 files changed, 148 insertions(+), 177 deletions(-) create mode 100644 docs/source/lang/api/shiftout.rst delete mode 100644 docs/source/lang/unimplemented/shiftout.rst (limited to 'wirish') diff --git a/docs/source/bootloader.rst b/docs/source/bootloader.rst index 57833ed..cfbf545 100644 --- a/docs/source/bootloader.rst +++ b/docs/source/bootloader.rst @@ -66,7 +66,7 @@ have embedded USB support. Thus, Maple doesn’t need the extra FTDI chip. Firmware is uploaded via the standard DFU protocol (also used by iPhone and openMoko). Since DFU is a standard, there is no need for custom software running on the host to upload the firmware. Any DFU -compliant program will work. The maple ide is based around +compliant program will work. The Maple IDE is based around :command:`dfu-util`, openMoko’s DFU utility. Using DFU came at a cost, however. The USB port must additionally implement a separate serial port at the same time (we use the CDC ACM class for serial @@ -87,11 +87,11 @@ important what this means, except for two things. 1. Four drivers were necessary to make everything work. 2. IAD is not supported by OS X. -Mac, on the other hand, only supported Compound USB, a different trick -that is not supported by Windows. While a perpetual background +Mac OS X, on the other hand, only supported Compound USB, a different +trick that is not supported by Windows. While a perpetual background bootloader was attractive, it became clear, after much toiling, we -were going to have to write some custom drivers across several -platforms to make everything work this way. +were going to have to write custom drivers across several platforms to +make everything work this way. .. _bootloader-rev3: @@ -103,22 +103,21 @@ Arduino. In Rev 3, the device resets into bootloader mode, which stays alive for a few moments to receive commands, and then jumps to user code. The bootloader is implemented as a DFU device -- just a DFU device, no serial port. This requires one driver for Windows -(:file:`drivers/mapleDrv/dfu` in the Windows IDE directory). As part -of the :ref:`libmaple ` library, user code is automatically -supplied with serial support via some behind the scenes work that -happens automatically when you compile (``setupUSB()`` is appended to -``setup()``). This user mode code only implements a CDC ACM class USB -device, giving you functions like ``Usb.print()``. Separating these -two modes fixed the driver issue, required no complicated compound USB -device nonsense, and works well across platforms, requiring only two -drivers (serial and DFU) on Windows. +(:file:`drivers/mapleDrv/dfu` in the Windows IDE directory). + +As part of the :ref:`libmaple ` library, user code is +automatically supplied with serial support via some behind the scenes +work (``setupUSB()`` is called from ``init()``). This user mode code +only implements a CDC ACM class USB device, giving you functions like +:ref:`SerialUSB.read() `. Separating these two +modes fixed the driver issues and works well across platforms, +requiring only two drivers (serial and DFU) on Windows. However, it is no longer possible to upload code at will, since there -is no bootloader quietly listening in the background. Instead you have -to reset the board, then initiate a DFU transaction. This reset is -performed automatically by the IDE by sending a command over the USB -serial port. You can generate this reset on your own using a Python -script or some other scheme. All you need do is: +is no bootloader quietly listening in the background. Instead, you +must reset the board, then initiate a DFU transaction. The IDE +performs this reset automatically by performing a special sequence of +changes on the USB serial port: 1. Pulse DTR (high and then low, so that you've created a negative edge) @@ -128,15 +127,16 @@ script or some other scheme. All you need do is: negative edge, rather than just ensuring DTR is low. After the reset, the host OS takes a few moments (.5-2 seconds) to -re-enumerate the device as DFU. This delay is unpredictable, and its -the reason the bootloader on Maple Rev3 stays alive for so -long. Sometimes the bootloader was exiting before the OS had even -enumerated the device! Once in bootloader mode, however, -:command:`dfu-util` uploads your sketch into either flash or RAM (DFU -alternate setting 0 or 1, respectively) and resets the board again. -This time, however, no DFU transaction is initiated, and the -bootloader gives way to user code, closing down the DFU pipe and -bringing up the USB serial. +re-enumerate the device as DFU. This delay is unpredictable, and is +the reason the bootloader on Maple Rev 3/Rev 5 stays alive for so +long. (Sometimes, the bootloader was exiting before the OS had even +enumerated the device.) + +Once in bootloader mode, :command:`dfu-util` uploads your sketch into +either flash or RAM (DFU alternate setting 0 or 1, respectively) and +resets the board again. This time, however, no DFU transaction is +initiated, and the bootloader gives way to user code, closing down the +DFU pipe and bringing up the USB serial port. .. .. _bootloader-rev6: diff --git a/docs/source/lang/api/constants.rst b/docs/source/lang/api/constants.rst index 72738b8..2e968e7 100644 --- a/docs/source/lang/api/constants.rst +++ b/docs/source/lang/api/constants.rst @@ -61,14 +61,6 @@ pin is configured as an ``INPUT`` (using :ref:`pinMode() `, the microcontroller will report ``HIGH`` if a voltage of 3 volts or more is present at the pin. -.. TODO? Following seems false; check it out sometime, leave out for now: - -.. A pin may also be configured as an ``INPUT`` with ``pinMode()``, and -.. subsequently made ``HIGH`` with :ref:`digitalWrite() -.. `, this will set the internal pullup resistors, -.. which will *steer* the input pin to a HIGH reading unless it is pulled -.. LOW by external circuitry. - When a pin is configured to ``OUTPUT`` with pinMode, and set to ``HIGH`` with :ref:`digitalWrite() `, the pin is at 3.3 volts. In this state it can *source* current, e.g. light an LED diff --git a/docs/source/lang/api/shiftout.rst b/docs/source/lang/api/shiftout.rst new file mode 100644 index 0000000..1d9ba12 --- /dev/null +++ b/docs/source/lang/api/shiftout.rst @@ -0,0 +1,99 @@ +.. highlight:: cpp + +.. _lang-shiftout: + +shiftOut() +========== + +Shift out a byte of data, one bit at a time. + +.. contents:: Contents + :local: + +Library Documentation +--------------------- + +.. doxygenfunction:: shiftOut + +Discussion +---------- + +This is a software implementation. There is also a hardware :ref:`SPI +` library available which will be faster and consume less CPU +cycles than this function. + +Note that the ``dataPin`` and ``clockPin`` must already be configured +to :ref:`OUTPUT ` mode by a call to +:ref:`pinMode() `. + +Also note that since shiftOut() outputs 1 byte (8 bits) at a time, it +requires multiple steps to output values larger than 255. + +Examples +-------- + +To use these examples, replace ``dataPin`` and ``clockPin`` with the +numbers of the pins you want to use:: + + /* MSBFIRST example */ + + uint16 data = 500; + // shift out high byte + shiftOut(dataPin, clockPin, MSBFIRST, (data >> 8)); + // shift out low byte + shiftOut(dataPin, clockPin, MSBFIRST, data); + + /* LSBFIRST serial */ + + data = 500; + // shift out low byte + shiftOut(dataPin, clockPin, LSBFIRST, data); + // shift out high byte + shiftOut(dataPin, clockPin, LSBFIRST, (data >> 8)); + +Arduino Tutorial Example +------------------------ + +This Arduino example runs unmodified on the Maple. For accompanying +circuit, see the `tutorial on controlling a 74HC595 shift register +`_. + +:: + + //**************************************************************// + // Name : shiftOutCode, Hello World // + // Author : Carlyn Maw, Tom Igoe // + // Date : 25 Oct, 2006 // + // Version : 1.0 // + // Notes : Code for using a 74HC595 Shift Register // + // : to count from 0 to 255 // + //**************************************************************// + + // Pin connected to ST_CP of 74HC595 + int latchPin = 8; + // Pin connected to SH_CP of 74HC595 + int clockPin = 12; + // Pin connected to DS of 74HC595 + int dataPin = 11; + + void setup() { + // Set pins to output because they are addressed in the main loop + pinMode(latchPin, OUTPUT); + pinMode(clockPin, OUTPUT); + pinMode(dataPin, OUTPUT); + } + + void loop() { + // Count up routine + for (int j = 0; j < 256; j++) { + // Ground latchPin and hold low for as long as you are transmitting + digitalWrite(latchPin, LOW); + shiftOut(dataPin, clockPin, LSBFIRST, j); + // Return the latch pin high to signal chip that it + // no longer needs to listen for information + digitalWrite(latchPin, HIGH); + delay(1000); + } + } + +.. include:: /lang/cc-attribution.txt diff --git a/docs/source/lang/unimplemented/shiftout.rst b/docs/source/lang/unimplemented/shiftout.rst deleted file mode 100644 index ff3852f..0000000 --- a/docs/source/lang/unimplemented/shiftout.rst +++ /dev/null @@ -1,136 +0,0 @@ -.. _lang-shiftout: - -shiftOut() -========== - -Description ------------ - -Shifts out a byte of data one bit at a time. Starts from either the -most (i.e. the leftmost) or least (rightmost) significant bit. Each -bit is written in turn to a data pin, after which a clock pin is -pulsed to indicate that the bit is available. - - - -This is a software implementation; Arduino (as of 0019) also -provides an `SPI library `_ -that uses the hardware implementation. - - - -Syntax ------- - -shiftOut(dataPin, clockPin, bitOrder, value) - - - -Parameters ----------- - -dataPin: the pin on which to output each bit (*int*) - - - -clockPin: the pin to toggle once the **dataPin** has been set to -the correct value (*int*) - - - -bitOrder: which order to shift out the bits; either **MSBFIRST** or -**LSBFIRST**. -(Most Significant Bit First, or, Least Significant Bit First) - - - -value: the data to shift out. (*byte*) - - - -Returns -------- - -None - - - -Note ----- - -The **dataPin** and **clockPin** must already be configured as -outputs by a call to -`pinMode `_\ (). - - - -**shiftOut** is currently written to output 1 byte (8 bits) so it -requires a two step operation to output values larger than 255. - -:: - - // Do this for MSBFIRST serial - int data = 500; - // shift out highbyte - shiftOut(dataPin, clock, MSBFIRST, (data >> 8)); - // shift out lowbyte - shiftOut(data, clock, MSBFIRST, data); - - // Or do this for LSBFIRST serial - data = 500; - // shift out lowbyte - shiftOut(dataPin, clock, LSBFIRST, data); - // shift out highbyte - shiftOut(dataPin, clock, LSBFIRST, (data >> 8)); - - - -Example -------- - -*For accompanying circuit, see the `tutorial on controlling a 74HC595 shift register `_.* - - - -:: - - //**************************************************************// - // Name : shiftOutCode, Hello World // - // Author : Carlyn Maw,Tom Igoe // - // Date : 25 Oct, 2006 // - // Version : 1.0 // - // Notes : Code for using a 74HC595 Shift Register // - // : to count from 0 to 255 // - //**************************************************************** - - //Pin connected to ST_CP of 74HC595 - int latchPin = 8; - //Pin connected to SH_CP of 74HC595 - int clockPin = 12; - ////Pin connected to DS of 74HC595 - int dataPin = 11; - - void setup() { - //set pins to output because they are addressed in the main loop - pinMode(latchPin, OUTPUT); - pinMode(clockPin, OUTPUT); - pinMode(dataPin, OUTPUT); - } - - void loop() { - //count up routine - for (int j = 0; j < 256; j++) { - //ground latchPin and hold low for as long as you are transmitting - digitalWrite(latchPin, LOW); - shiftOut(dataPin, clockPin, LSBFIRST, j); - //return the latch pin high to signal chip that it - //no longer needs to listen for information - digitalWrite(latchPin, HIGH); - delay(1000); - } - } - - - - -.. include:: /lang/cc-attribution.txt diff --git a/docs/source/language-index.rst b/docs/source/language-index.rst index 3c55c33..c949988 100644 --- a/docs/source/language-index.rst +++ b/docs/source/language-index.rst @@ -33,7 +33,6 @@ programmers familiar with the Arduino language. lang/unimplemented/notone.rst lang/unimplemented/pulsein.rst - lang/unimplemented/shiftout.rst lang/unimplemented/stringclass.rst lang/unimplemented/stringobject.rst lang/unimplemented/tone.rst diff --git a/docs/source/language.rst b/docs/source/language.rst index b2f4650..d340aec 100644 --- a/docs/source/language.rst +++ b/docs/source/language.rst @@ -61,7 +61,7 @@ A more exhaustive index is available at the :ref:`language-index`. | |* :ref:`boolean ` (1 byte) | | |* :ref:`{} (curly braces) | |* noTone(): TODO | | ` |* :ref:`char ` (1 byte) | | -| | |* shiftOut(): TODO | +| | |* :ref:`shiftOut() ` | |* :ref:`// (single-line comment) |* :ref:`unsigned char | | | ` | ` (1 byte) |* pulseIn(): TODO | | | | | @@ -187,11 +187,13 @@ A more exhaustive index is available at the :ref:`language-index`. | | | | +--------------------------------------------+----------------------------------------------+---------------------------------------------------+ +.. _language-assert: + ``ASSERT(...)`` --------------- The ``ASSERT()`` function can be very useful for basic program -debugging. The function accepts a boolean; for example:: +debugging. It accepts a boolean; for example:: ASSERT(state == WAIT); @@ -255,11 +257,10 @@ Unimplemented Arduino Features The following Wiring/Arduino features are currently unimplemented on the Maple. However, they will be present in future versions: +- `tone() `_ - `noTone() `_ - `pulseIn() `_ -- `shiftOut() `_ - `String `_ -- `tone() `_ .. _our reference page: http://leaflabs.com/docs/external-interrupts/ diff --git a/wirish/io.h b/wirish/io.h index d2e4d2d..8dad1d1 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -216,5 +216,21 @@ uint8 isButtonPressed(); */ uint8 waitForButtonPress(uint32 timeout_millis); +/** + * Shift out a byte of data, one bit at a time. + * + * This function starts at either the most significant or least + * significant bit in a byte value, and shifts out each byte in order + * onto a data pin. After each bit is written to the data pin, a + * separate clock pin is pulsed to indicate that the new bit is + * available. + * + * @param dataPin Pin to shift data out on + * @param clockPin Pin to pulse after each bit is shifted out + * @param bitOrder Either MSBFIRST (big-endian) or LSBFIRST (little-endian). + * @param val Value to shift out + */ +void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 value); + #endif -- cgit v1.2.3 From e3fae0984dab4f1044ea3ffc1aa41b2df12370b2 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Sat, 12 Mar 2011 23:28:53 -0500 Subject: RCC refactor, bugfixes --- libmaple/adc.c | 4 +- libmaple/adc.h | 6 +- libmaple/bkp.c | 4 +- libmaple/dac.c | 4 + libmaple/dac.h | 4 + libmaple/exti.c | 18 +- libmaple/gpio.c | 2 +- libmaple/rcc.c | 200 ++++++++++++-------- libmaple/rcc.h | 541 +++++++++++++++++++++++++++++++++++++++++++----------- wirish/boards.cpp | 2 +- wirish/wirish.cpp | 2 +- 11 files changed, 575 insertions(+), 212 deletions(-) (limited to 'wirish') diff --git a/libmaple/adc.c b/libmaple/adc.c index 9626a40..3d38596 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -126,8 +126,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { * @param dev adc device */ static void adc_calibrate(const adc_dev *dev) { - __io uint32 *rstcal_bit = bb_peripv(&(dev->regs->CR2), 3); - __io uint32 *cal_bit = bb_peripv(&(dev->regs->CR2), 2); + __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3); + __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2); *rstcal_bit = 1; while (*rstcal_bit) diff --git a/libmaple/adc.h b/libmaple/adc.h index 4811dbc..53ef032 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -175,7 +175,7 @@ static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { * @param enable If 1, conversion on external events is enabled, 0 to disable */ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { - *bb_peripv(&dev->regs->CR2, 20) = !!enable; + *bb_perip(&dev->regs->CR2, 20) = !!enable; } /** @@ -183,7 +183,7 @@ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { * @param dev ADC device to enable */ static inline void adc_enable(const adc_dev *dev) { - *bb_peripv(&dev->regs->CR2, 0) = 1; + *bb_perip(&dev->regs->CR2, 0) = 1; } /** @@ -191,7 +191,7 @@ static inline void adc_enable(const adc_dev *dev) { * @param dev ADC device to disable */ static inline void adc_disable(const adc_dev *dev) { - *bb_peripv(&dev->regs->CR2, 0) = 0; + *bb_perip(&dev->regs->CR2, 0) = 0; } /** diff --git a/libmaple/bkp.c b/libmaple/bkp.c index b152069..aaccb1f 100644 --- a/libmaple/bkp.c +++ b/libmaple/bkp.c @@ -57,14 +57,14 @@ void bkp_init(void) { * @see bkp_init() */ void bkp_enable_writes(void) { - *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 1; + *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 1; } /** * Disable write access to the backup registers. */ void bkp_disable_writes(void) { - *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 0; + *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 0; } /** diff --git a/libmaple/dac.c b/libmaple/dac.c index ef3a9f9..f0bdbcd 100644 --- a/libmaple/dac.c +++ b/libmaple/dac.c @@ -26,6 +26,8 @@ #include "gpio.h" #include "dac.h" +#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + /** * @brief DAC peripheral routines. */ @@ -108,3 +110,5 @@ void dac_disable_channel(uint8 channel) { break; } } + +#endif diff --git a/libmaple/dac.h b/libmaple/dac.h index c897bb2..ee8a4e7 100644 --- a/libmaple/dac.h +++ b/libmaple/dac.h @@ -32,6 +32,8 @@ #ifndef _DAC_H_ #define _DAC_H_ +#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + #include "rcc.h" #ifdef __cplusplus @@ -149,4 +151,6 @@ void dac_disable_channel(uint8 channel); } // extern "C" #endif +#endif /* STM32_HIGH_DENSITY, STM32_XL_DENSITY */ + #endif diff --git a/libmaple/exti.c b/libmaple/exti.c index 8177e1e..7f56712 100644 --- a/libmaple/exti.c +++ b/libmaple/exti.c @@ -98,14 +98,14 @@ void exti_attach_interrupt(afio_exti_num num, /* Set trigger mode */ switch (mode) { case EXTI_RISING: - *bb_peripv(&EXTI_BASE->RTSR, num) = 1; + *bb_perip(&EXTI_BASE->RTSR, num) = 1; break; case EXTI_FALLING: - *bb_peripv(&EXTI_BASE->FTSR, num) = 1; + *bb_perip(&EXTI_BASE->FTSR, num) = 1; break; case EXTI_RISING_FALLING: - *bb_peripv(&EXTI_BASE->RTSR, num) = 1; - *bb_peripv(&EXTI_BASE->FTSR, num) = 1; + *bb_perip(&EXTI_BASE->RTSR, num) = 1; + *bb_perip(&EXTI_BASE->FTSR, num) = 1; break; } @@ -113,7 +113,7 @@ void exti_attach_interrupt(afio_exti_num num, afio_exti_select(num, port); /* Unmask external interrupt request */ - *bb_peripv(&EXTI_BASE->IMR, num) = 1; + *bb_perip(&EXTI_BASE->IMR, num) = 1; /* Enable the interrupt line */ enable_irq(num); @@ -126,11 +126,11 @@ void exti_attach_interrupt(afio_exti_num num, */ void exti_detach_interrupt(afio_exti_num num) { /* First, mask the interrupt request */ - *bb_peripv(&EXTI_BASE->IMR, num) = 0; + *bb_perip(&EXTI_BASE->IMR, num) = 0; /* Then, clear the trigger selection registers */ - *bb_peripv(&EXTI_BASE->FTSR, num) = 0; - *bb_peripv(&EXTI_BASE->RTSR, num) = 0; + *bb_perip(&EXTI_BASE->FTSR, num) = 0; + *bb_perip(&EXTI_BASE->RTSR, num) = 0; /* Next, disable the IRQ, unless it's multiplexed and there are * other active external interrupts on the same IRQ line */ @@ -210,7 +210,7 @@ void __irq_exti15_10(void) { */ static inline void clear_pending(uint32 exti_num) { - *bb_peripv(&EXTI_BASE->PR, exti_num) = 1; + *bb_perip(&EXTI_BASE->PR, exti_num) = 1; /* If the pending bit is cleared as the last instruction in an ISR, * it won't actually be cleared in time and the ISR will fire again. * Insert a 2-cycle buffer to allow it to take effect. */ diff --git a/libmaple/gpio.c b/libmaple/gpio.c index b08be12..90be033 100644 --- a/libmaple/gpio.c +++ b/libmaple/gpio.c @@ -61,7 +61,7 @@ static gpio_dev gpiod = { /** GPIO port D device. */ gpio_dev *GPIOD = &gpiod; -#ifdef STM32_HIGH_ +#ifdef STM32_HIGH_DENSITY static gpio_dev gpioe = { .regs = GPIOE_BASE, .clk_id = RCC_GPIOE diff --git a/libmaple/rcc.c b/libmaple/rcc.c index 2841af3..e49382c 100644 --- a/libmaple/rcc.c +++ b/libmaple/rcc.c @@ -23,97 +23,115 @@ *****************************************************************************/ /** - * @brief Implements pretty much only the basic clock setup on the - * stm32, clock enable/disable and peripheral reset commands. + * @file rcc.c + * @brief Clock setup, peripheral enable and reset routines. */ #include "libmaple.h" #include "flash.h" #include "rcc.h" +#include "bitband.h" -enum { +typedef enum clock_domain { APB1, APB2, AHB -}; +} clock_domain; struct rcc_dev_info { - const uint8 clk_domain; + const clock_domain clk_domain; const uint8 line_num; }; /* device descriptor tables */ -static const struct rcc_dev_info rcc_dev_table[] = { - [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 }, - [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 }, - [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 }, - [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 }, - [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 }, // High-density only - [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 }, // High-density only - [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 }, // High-density only - [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 }, - [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 }, - [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 }, - [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 }, - [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 }, - [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 }, - [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 }, - [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, // High-density only - [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, // High-density only - [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 }, - [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 }, - [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 }, - [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 }, - [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, // High-density only - [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, // High-density only - [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, // High-density only - [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 }, // High-density only - [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 }, - [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 }, - [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 }, // High-density only - [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, // High-density only - [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 }, - [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, // High-density only - [RCC_PWR] = { .clk_domain = APB1, .line_num = 28}, - [RCC_BKP] = { .clk_domain = APB1, .line_num = 27} +static const __attr_flash struct rcc_dev_info rcc_dev_table[] = { + [RCC_SRAM] = { .clk_domain = AHB, .line_num = 2 }, + [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 }, + [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 }, + [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 }, + [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 }, + [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 }, + [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 }, + [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 }, + [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 }, + [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 }, + [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 }, + [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 }, + [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 }, + [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 }, + [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 }, + [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 }, + [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 }, + [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 }, + [RCC_PWR] = { .clk_domain = APB1, .line_num = 28 }, + [RCC_BKP] = { .clk_domain = APB1, .line_num = 27 }, + [RCC_CAN] = { .clk_domain = APB1, .line_num = 25 }, + [RCC_USB] = { .clk_domain = APB1, .line_num = 23 }, + [RCC_I2C1] = { .clk_domain = APB1, .line_num = 22 }, + [RCC_I2C2] = { .clk_domain = APB1, .line_num = 21 }, + [RCC_CRC] = { .clk_domain = AHB, .line_num = 6 }, + [RCC_WWDG] = { .clk_domain = APB2, .line_num = 11 }, + [RCC_FLITF] = { .clk_domain = AHB, .line_num = 4 }, +#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + [RCC_SDIO] = { .clk_domain = AHB, .line_num = 10 }, + [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 }, + [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 }, + [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 }, + [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 }, + [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 }, + [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, + [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, + [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, + [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, + [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, + [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 }, + [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, + [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, + [RCC_SPI3] = { .clk_domain = APB1, .line_num = 15 }, +#endif +#ifdef STM32_XL_DENSITY + [RCC_TIMER9] = { .clk_domain = APB2, .line_num = 19 }, + [RCC_TIMER10] = { .clk_domain = APB2, .line_num = 20 }, + [RCC_TIMER11] = { .clk_domain = APB2, .line_num = 21 }, + [RCC_TIMER12] = { .clk_domain = APB1, .line_num = 6 }, + [RCC_TIMER13] = { .clk_domain = APB1, .line_num = 7 }, + [RCC_TIMER14] = { .clk_domain = APB1, .line_num = 8 }, +#endif }; /** * @brief Initialize the clock control system. Initializes the system * clock source to use the PLL driven by an external oscillator * @param sysclk_src system clock source, must be PLL - * @param pll_src pll clock source, must be HSE + * @param pll_src pll clock source, must be RCC_CFGR_PLLSRC_HSE * @param pll_mul pll multiplier */ void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) { + uint32 cfgr; + /* Assume that we're going to clock the chip off the PLL, fed by * the HSE */ ASSERT(sysclk_src == RCC_CLKSRC_PLL && - pll_src == RCC_PLLSRC_HSE); - - uint32 cfgr = 0; - uint32 cr = RCC_READ_CR(); + pll_src == RCC_CFGR_PLLSRC_HSE); - cfgr = (pll_src | pll_mul); - RCC_WRITE_CFGR(cfgr); + RCC_BASE->CFGR = pll_src | pll_mul; - /* Turn on the HSE */ - cr |= RCC_CR_HSEON; - RCC_WRITE_CR(cr); - while (!(RCC_READ_CR() & RCC_CR_HSERDY)) + /* Turn on the HSE */ + *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1; + while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_HSERDY_BIT))) ; - /* Now the PLL */ - cr |= RCC_CR_PLLON; - RCC_WRITE_CR(cr); - while (!(RCC_READ_CR() & RCC_CR_PLLRDY)) + /* Now the PLL */ + *bb_perip(&RCC_BASE->CR, RCC_CR_PLLON_BIT) = 1; + while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_PLLRDY_BIT))) ; /* Finally, let's switch over to the PLL */ + cfgr = RCC_BASE->CFGR; cfgr &= ~RCC_CFGR_SW; cfgr |= RCC_CFGR_SW_PLL; - RCC_WRITE_CFGR(cfgr); - while ((RCC_READ_CFGR() & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL) + RCC_BASE->CFGR = cfgr; + while ((RCC_BASE->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL) ; } @@ -121,16 +139,23 @@ void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) { * @brief Turn on the clock line on a device * @param device Clock ID of the device to turn on. */ -void rcc_clk_enable(rcc_clk_id device) { - static const uint32 enable_regs[] = { - [APB1] = RCC_APB1ENR, - [APB2] = RCC_APB2ENR, - [AHB] = RCC_AHBENR, - }; - - uint8 clk_domain = rcc_dev_table[device].clk_domain; - - __set_bits(enable_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); +void rcc_clk_enable(rcc_clk_id id) { + uint8 lnum = rcc_dev_table[id].line_num; + __io uint32 *enr; + + switch(rcc_dev_table[id].clk_domain) { + case APB1: + enr = &RCC_BASE->APB1ENR; + break; + case APB2: + enr = &RCC_BASE->APB2ENR; + break; + case AHB: + enr = &RCC_BASE->AHBENR; + break; + } + + *bb_perip(enr, lnum) = 1; } /** @@ -138,7 +163,7 @@ void rcc_clk_enable(rcc_clk_id device) { * @param prescaler prescaler to set * @param divider prescaler divider */ -void rcc_set_prescaler(uint32 prescaler, uint32 divider) { +void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) { static const uint32 masks[] = { [RCC_PRESCALER_AHB] = RCC_CFGR_HPRE, [RCC_PRESCALER_APB1] = RCC_CFGR_PPRE1, @@ -146,26 +171,39 @@ void rcc_set_prescaler(uint32 prescaler, uint32 divider) { [RCC_PRESCALER_USB] = RCC_CFGR_USBPRE, [RCC_PRESCALER_ADC] = RCC_CFGR_ADCPRE, }; + uint32 cfgr; - uint32 cfgr = RCC_READ_CFGR(); - + cfgr = RCC_BASE->CFGR; cfgr &= ~masks[prescaler]; cfgr |= divider; - RCC_WRITE_CFGR(cfgr); + RCC_BASE->CFGR = cfgr; } /** - * @brief reset a device - * @param device Clock ID of the device to reset. + * @brief Reset a device + * @param device Clock ID of the device to reset; the device must be + * on APB1 or APB2. */ -void rcc_reset_dev(rcc_clk_id device) { - static const uint32 reset_regs[] = { - [APB1] = RCC_APB1RSTR, - [APB2] = RCC_APB2RSTR, - }; - - uint8 clk_domain = rcc_dev_table[device].clk_domain; - - __set_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); - __clear_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); +void rcc_reset_dev(rcc_clk_id id) { + uint8 lnum = rcc_dev_table[id].line_num; + __io uint32 *rstr = 0; + + switch (rcc_dev_table[id].clk_domain) { + case APB1: + rstr = &RCC_BASE->APB1RSTR; + break; + case APB2: + rstr = &RCC_BASE->APB2RSTR; + break; + case AHB: + ASSERT(0); + break; + } + + if (rstr == 0) { + return; + } + + *bb_perip(rstr, lnum) = 1; + *bb_perip(rstr, lnum) = 0; } diff --git a/libmaple/rcc.h b/libmaple/rcc.h index 8697e01..83b34ed 100644 --- a/libmaple/rcc.h +++ b/libmaple/rcc.h @@ -24,7 +24,7 @@ /** * @file rcc.h - * @brief reset and clock control definitions and prototypes + * @brief Reset and clock control (RCC) definitions and prototypes */ #include "libmaple_types.h" @@ -36,78 +36,451 @@ extern "C"{ #endif -/* registers */ -#define RCC_BASE 0x40021000 -#define RCC_CR (RCC_BASE + 0x0) -#define RCC_CFGR (RCC_BASE + 0x4) -#define RCC_CIR (RCC_BASE + 0x8) -#define RCC_APB2RSTR (RCC_BASE + 0xC) -#define RCC_APB1RSTR (RCC_BASE + 0x10) -#define RCC_AHBENR (RCC_BASE + 0x14) -#define RCC_APB2ENR (RCC_BASE + 0x18) -#define RCC_APB1ENR (RCC_BASE + 0x1C) -#define RCC_BDCR (RCC_BASE + 0x20) -#define RCC_CSR (RCC_BASE + 0x24) -#define RCC_AHBSTR (RCC_BASE + 0x28) -#define RCC_CFGR2 (RCC_BASE + 0x2C) - -#define RCC_CFGR_USBPRE (0x1 << 22) -#define RCC_CFGR_ADCPRE (0x3 << 14) -#define RCC_CFGR_PPRE1 (0x7 << 8) -#define RCC_CFGR_PPRE2 (0x7 << 11) -#define RCC_CFGR_HPRE (0xF << 4) -#define RCC_CFGR_PLLSRC (0x1 << 16) - -#define RCC_CFGR_SWS (0x3 << 2) -#define RCC_CFGR_SWS_PLL (0x2 << 2) -#define RCC_CFGR_SWS_HSE (0x1 << 2) - -#define RCC_CFGR_SW (0x3 << 0) -#define RCC_CFGR_SW_PLL (0x2 << 0) -#define RCC_CFGR_SW_HSE (0x1 << 0) - -/* CR status bits */ -#define RCC_CR_HSEON (0x1 << 16) -#define RCC_CR_HSERDY (0x1 << 17) -#define RCC_CR_PLLON (0x1 << 24) -#define RCC_CR_PLLRDY (0x1 << 25) - -#define RCC_WRITE_CFGR(val) __write(RCC_CFGR, val) -#define RCC_READ_CFGR() __read(RCC_CFGR) - -#define RCC_WRITE_CR(val) __write(RCC_CR, val) -#define RCC_READ_CR() __read(RCC_CR) - -/* sysclk source */ +/** RCC register map type */ +typedef struct rcc_reg_map { + __io uint32 CR; /**< Clock control register */ + __io uint32 CFGR; /**< Clock configuration register */ + __io uint32 CIR; /**< Clock interrupt register */ + __io uint32 APB2RSTR; /**< APB2 peripheral reset register */ + __io uint32 APB1RSTR; /**< APB1 peripheral reset register */ + __io uint32 AHBENR; /**< AHB peripheral clock enable register */ + __io uint32 APB2ENR; /**< APB2 peripheral clock enable register */ + __io uint32 APB1ENR; /**< APB1 peripheral clock enable register */ + __io uint32 BDCR; /**< Backup domain control register */ + __io uint32 CSR; /**< Control/status register */ +} rcc_reg_map; + +/* + * RCC register map base address + */ + +#define RCC_BASE ((rcc_reg_map*)0x40021000) + +/* + * RCC register bit definitions + */ + +/* Clock control register */ + +#define RCC_CR_PLLRDY_BIT 25 +#define RCC_CR_PLLON_BIT 24 +#define RCC_CR_CSSON_BIT 19 +#define RCC_CR_HSEBYP_BIT 18 +#define RCC_CR_HSERDY_BIT 17 +#define RCC_CR_HSEON_BIT 16 +#define RCC_CR_HSIRDY_BIT 1 +#define RCC_CR_HSION_BIT 0 + +#define RCC_CR_PLLRDY BIT(RCC_CR_PLLRDY_BIT) +#define RCC_CR_PLLON BIT(RCC_CR_PLLON_BIT) +#define RCC_CR_CSSON BIT(RCC_CR_CSSON_BIT) +#define RCC_CR_HSEBYP BIT(RCC_CR_HSEBYP_BIT) +#define RCC_CR_HSERDY BIT(RCC_CR_HSERDY_BIT) +#define RCC_CR_HSEON BIT(RCC_CR_HSEON_BIT) +#define RCC_CR_HSICAL (0xFF << 8) +#define RCC_CR_HSITRIM (0x1F << 3) +#define RCC_CR_HSIRDY BIT(RCC_CR_HSIRDY_BIT) +#define RCC_CR_HSION BIT(RCC_CR_HSION_BIT) + +/* Clock configuration register */ + +#define RCC_CFGR_USBPRE_BIT 22 +#define RCC_CFGR_PLLXTPRE_BIT 17 +#define RCC_CFGR_PLLSRC_BIT 16 + +#define RCC_CFGR_MCO (0x7 << 24) +#define RCC_CFGR_USBPRE BIT(RCC_CFGR_USBPRE_BIT) +#define RCC_CFGR_PLLMUL (0xF << 18) +#define RCC_CFGR_PLLMUL_2 (0x0 << 18) +#define RCC_CFGR_PLLMUL_3 (0x1 << 18) +#define RCC_CFGR_PLLMUL_4 (0x2 << 18) +#define RCC_CFGR_PLLMUL_5 (0x3 << 18) +#define RCC_CFGR_PLLMUL_6 (0x4 << 18) +#define RCC_CFGR_PLLMUL_7 (0x5 << 18) +#define RCC_CFGR_PLLMUL_8 (0x6 << 18) +#define RCC_CFGR_PLLMUL_9 (0x7 << 18) +#define RCC_CFGR_PLLMUL_10 (0x8 << 18) +#define RCC_CFGR_PLLMUL_11 (0x9 << 18) +#define RCC_CFGR_PLLMUL_12 (0xA << 18) +#define RCC_CFGR_PLLMUL_13 (0xB << 18) +#define RCC_CFGR_PLLMUL_14 (0xC << 18) +#define RCC_CFGR_PLLMUL_15 (0xD << 18) +#define RCC_CFGR_PLLMUL_16 (0xE << 18) +#define RCC_CFGR_PLLXTPRE BIT(RCC_CFGR_PLLXTPRE_BIT) +#define RCC_CFGR_PLLSRC BIT(RCC_CFGR_PLLSRC_BIT) +#define RCC_CFGR_PLLSRC_HSI_DIV_2 (0 << RCC_CFGR_PLLSRC_BIT) +#define RCC_CFGR_PLLSRC_HSE (1 << RCC_CFGR_PLLSRC_BIT) +#define RCC_CFGR_ADCPRE (0x3 << 14) +#define RCC_CFGR_PPRE2 (0x7 << 11) +#define RCC_CFGR_PPRE1 (0x7 << 8) +#define RCC_CFGR_HPRE (0xF << 4) +#define RCC_CFGR_SWS (0x3 << 2) +#define RCC_CFGR_SWS_PLL (0x2 << 2) +#define RCC_CFGR_SWS_HSE (0x1 << 2) +#define RCC_CFGR_SW (0x3 << 0) +#define RCC_CFGR_SW_PLL (0x2 << 0) +#define RCC_CFGR_SW_HSE (0x1 << 0) + +/* Clock interrupt register */ + +#define RCC_CIR_CSSC_BIT 23 +#define RCC_CIR_PLLRDYC_BIT 20 +#define RCC_CIR_HSERDYC_BIT 19 +#define RCC_CIR_HSIRDYC_BIT 18 +#define RCC_CIR_LSERDYC_BIT 17 +#define RCC_CIR_LSIRDYC_BIT 16 +#define RCC_CIR_PLLRDYIE_BIT 12 +#define RCC_CIR_HSERDYIE_BIT 11 +#define RCC_CIR_HSIRDYIE_BIT 10 +#define RCC_CIR_LSERDYIE_BIT 9 +#define RCC_CIR_LSIRDYIE_BIT 8 +#define RCC_CIR_CSSF_BIT 7 +#define RCC_CIR_PLLRDYF_BIT 4 +#define RCC_CIR_HSERDYF_BIT 3 +#define RCC_CIR_HSIRDYF_BIT 2 +#define RCC_CIR_LSERDYF_BIT 1 +#define RCC_CIR_LSIRDYF_BIT 0 + +#define RCC_CIR_CSSC BIT(RCC_CIR_CSSC_BIT) +#define RCC_CIR_PLLRDYC BIT(RCC_CIR_PLLRDYC_BIT) +#define RCC_CIR_HSERDYC BIT(RCC_CIR_HSERDYC_BIT) +#define RCC_CIR_HSIRDYC BIT(RCC_CIR_HSIRDYC_BIT) +#define RCC_CIR_LSERDYC BIT(RCC_CIR_LSERDYC_BIT) +#define RCC_CIR_LSIRDYC BIT(RCC_CIR_LSIRDYC_BIT) +#define RCC_CIR_PLLRDYIE BIT(RCC_CIR_PLLRDYIE_BIT) +#define RCC_CIR_HSERDYIE BIT(RCC_CIR_HSERDYIE_BIT) +#define RCC_CIR_HSIRDYIE BIT(RCC_CIR_HSIRDYIE_BIT) +#define RCC_CIR_LSERDYIE BIT(RCC_CIR_LSERDYIE_BIT) +#define RCC_CIR_LSIRDYIE BIT(RCC_CIR_LSIRDYIE_BIT) +#define RCC_CIR_CSSF BIT(RCC_CIR_CSSF_BIT) +#define RCC_CIR_PLLRDYF BIT(RCC_CIR_PLLRDYF_BIT) +#define RCC_CIR_HSERDYF BIT(RCC_CIR_HSERDYF_BIT) +#define RCC_CIR_HSIRDYF BIT(RCC_CIR_HSIRDYF_BIT) +#define RCC_CIR_LSERDYF BIT(RCC_CIR_LSERDYF_BIT) +#define RCC_CIR_LSIRDYF BIT(RCC_CIR_LSIRDYF_BIT) + +/* APB2 peripheral reset register */ + +#define RCC_APB2RSTR_TIM11RST_BIT 21 +#define RCC_APB2RSTR_TIM10RST_BIT 20 +#define RCC_APB2RSTR_TIM9RST_BIT 19 +#define RCC_APB2RSTR_ADC3RST_BIT 15 +#define RCC_APB2RSTR_USART1RST_BIT 14 +#define RCC_APB2RSTR_TIM8RST_BIT 13 +#define RCC_APB2RSTR_SPI1RST_BIT 12 +#define RCC_APB2RSTR_TIM1RST_BIT 11 +#define RCC_APB2RSTR_ADC2RST_BIT 10 +#define RCC_APB2RSTR_ADC1RST_BIT 9 +#define RCC_APB2RSTR_IOPGRST_BIT 8 +#define RCC_APB2RSTR_IOPFRST_BIT 7 +#define RCC_APB2RSTR_IOPERST_BIT 6 +#define RCC_APB2RSTR_IOPDRST_BIT 5 +#define RCC_APB2RSTR_IOPCRST_BIT 4 +#define RCC_APB2RSTR_IOPBRST_BIT 3 +#define RCC_APB2RSTR_IOPARST_BIT 2 +#define RCC_APB2RSTR_AFIORST_BIT 0 + +#define RCC_APB2RSTR_TIM11RST BIT(RCC_APB2RSTR_TIM11RST_BIT) +#define RCC_APB2RSTR_TIM10RST BIT(RCC_APB2RSTR_TIM10RST_BIT) +#define RCC_APB2RSTR_TIM9RST BIT(RCC_APB2RSTR_TIM9RST_BIT) +#define RCC_APB2RSTR_ADC3RST BIT(RCC_APB2RSTR_ADC3RST_BIT) +#define RCC_APB2RSTR_USART1RST BIT(RCC_APB2RSTR_USART1RST_BIT) +#define RCC_APB2RSTR_TIM8RST BIT(RCC_APB2RSTR_TIM8RST_BIT) +#define RCC_APB2RSTR_SPI1RST BIT(RCC_APB2RSTR_SPI1RST_BIT) +#define RCC_APB2RSTR_TIM1RST BIT(RCC_APB2RSTR_TIM1RST_BIT) +#define RCC_APB2RSTR_ADC2RST BIT(RCC_APB2RSTR_ADC2RST_BIT) +#define RCC_APB2RSTR_ADC1RST BIT(RCC_APB2RSTR_ADC1RST_BIT) +#define RCC_APB2RSTR_IOPGRST BIT(RCC_APB2RSTR_IOPGRST_BIT) +#define RCC_APB2RSTR_IOPFRST BIT(RCC_APB2RSTR_IOPFRST_BIT) +#define RCC_APB2RSTR_IOPERST BIT(RCC_APB2RSTR_IOPERST_BIT) +#define RCC_APB2RSTR_IOPDRST BIT(RCC_APB2RSTR_IOPDRST_BIT) +#define RCC_APB2RSTR_IOPCRST BIT(RCC_APB2RSTR_IOPCRST_BIT) +#define RCC_APB2RSTR_IOPBRST BIT(RCC_APB2RSTR_IOPBRST_BIT) +#define RCC_APB2RSTR_IOPARST BIT(RCC_APB2RSTR_IOPARST_BIT) +#define RCC_APB2RSTR_AFIORST BIT(RCC_APB2RSTR_AFIORST_BIT) + +/* APB1 peripheral reset register */ + +#define RCC_APB1RSTR_DACRST_BIT 29 +#define RCC_APB1RSTR_PWRRST_BIT 28 +#define RCC_APB1RSTR_BKPRST_BIT 27 +#define RCC_APB1RSTR_CANRST_BIT 25 +#define RCC_APB1RSTR_USBRST_BIT 23 +#define RCC_APB1RSTR_I2C2RST_BIT 22 +#define RCC_APB1RSTR_I2C1RST_BIT 21 +#define RCC_APB1RSTR_UART5RST_BIT 20 +#define RCC_APB1RSTR_UART4RST_BIT 19 +#define RCC_APB1RSTR_UART3RST_BIT 18 +#define RCC_APB1RSTR_UART2RST_BIT 17 +#define RCC_APB1RSTR_SPI3RST_BIT 15 +#define RCC_APB1RSTR_SPI2RST_BIT 14 +#define RCC_APB1RSTR_WWDGRST_BIT 11 +#define RCC_APB1RSTR_TIM14RST_BIT 8 +#define RCC_APB1RSTR_TIM13RST_BIT 7 +#define RCC_APB1RSTR_TIM12RST_BIT 6 +#define RCC_APB1RSTR_TIM7RST_BIT 5 +#define RCC_APB1RSTR_TIM6RST_BIT 4 +#define RCC_APB1RSTR_TIM5RST_BIT 3 +#define RCC_APB1RSTR_TIM4RST_BIT 2 +#define RCC_APB1RSTR_TIM3RST_BIT 1 +#define RCC_APB1RSTR_TIM2RST_BIT 0 + +#define RCC_APB1RSTR_DACRST BIT(RCC_APB1RSTR_DACRST_BIT) +#define RCC_APB1RSTR_PWRRST BIT(RCC_APB1RSTR_PWRRST_BIT) +#define RCC_APB1RSTR_BKPRST BIT(RCC_APB1RSTR_BKPRST_BIT) +#define RCC_APB1RSTR_CANRST BIT(RCC_APB1RSTR_CANRST_BIT) +#define RCC_APB1RSTR_USBRST BIT(RCC_APB1RSTR_USBRST_BIT) +#define RCC_APB1RSTR_I2C2RST BIT(RCC_APB1RSTR_I2C2RST_BIT) +#define RCC_APB1RSTR_I2C1RST BIT(RCC_APB1RSTR_I2C1RST_BIT) +#define RCC_APB1RSTR_UART5RST BIT(RCC_APB1RSTR_UART5RST_BIT) +#define RCC_APB1RSTR_UART4RST BIT(RCC_APB1RSTR_UART4RST_BIT) +#define RCC_APB1RSTR_UART3RST BIT(RCC_APB1RSTR_UART3RST_BIT) +#define RCC_APB1RSTR_UART2RST BIT(RCC_APB1RSTR_UART2RST_BIT) +#define RCC_APB1RSTR_SPI3RST BIT(RCC_APB1RSTR_SPI3RST_BIT) +#define RCC_APB1RSTR_SPI2RST BIT(RCC_APB1RSTR_SPI2RST_BIT) +#define RCC_APB1RSTR_WWDGRST BIT(RCC_APB1RSTR_WWDGRST_BIT) +#define RCC_APB1RSTR_TIM14RST BIT(RCC_APB1RSTR_TIM14RST_BIT) +#define RCC_APB1RSTR_TIM13RST BIT(RCC_APB1RSTR_TIM13RST_BIT) +#define RCC_APB1RSTR_TIM12RST BIT(RCC_APB1RSTR_TIM12RST_BIT) +#define RCC_APB1RSTR_TIM7RST BIT(RCC_APB1RSTR_TIM7RST_BIT) +#define RCC_APB1RSTR_TIM6RST BIT(RCC_APB1RSTR_TIM6RST_BIT) +#define RCC_APB1RSTR_TIM5RST BIT(RCC_APB1RSTR_TIM5RST_BIT) +#define RCC_APB1RSTR_TIM4RST BIT(RCC_APB1RSTR_TIM4RST_BIT) +#define RCC_APB1RSTR_TIM3RST BIT(RCC_APB1RSTR_TIM3RST_BIT) +#define RCC_APB1RSTR_TIM2RST BIT(RCC_APB1RSTR_TIM2RST_BIT) + +/* AHB peripheral clock enable register */ + +#define RCC_AHBENR_SDIOEN_BIT 10 +#define RCC_AHBENR_FSMCEN_BIT 8 +#define RCC_AHBENR_CRCEN_BIT 6 +#define RCC_AHBENR_FLITFEN_BIT 4 +#define RCC_AHBENR_SRAMEN_BIT 2 +#define RCC_AHBENR_DMA2EN_BIT 1 +#define RCC_AHBENR_DMA1EN_BIT 0 + +#define RCC_AHBENR_SDIOEN BIT(RCC_AHBENR_SDIOEN_BIT) +#define RCC_AHBENR_FSMCEN BIT(RCC_AHBENR_FSMCEN_BIT) +#define RCC_AHBENR_CRCEN BIT(RCC_AHBENR_CRCEN_BIT) +#define RCC_AHBENR_FLITFEN BIT(RCC_AHBENR_FLITFEN_BIT) +#define RCC_AHBENR_SRAMEN BIT(RCC_AHBENR_SRAMEN_BIT) +#define RCC_AHBENR_DMA2EN BIT(RCC_AHBENR_DMA2EN_BIT) +#define RCC_AHBENR_DMA1EN BIT(RCC_AHBENR_DMA1EN_BIT) + +/* APB2 peripheral clock enable register */ + +#define RCC_APB2ENR_TIM11EN_BIT 21 +#define RCC_APB2ENR_TIM10EN_BIT 20 +#define RCC_APB2ENR_TIM9EN_BIT 19 +#define RCC_APB2ENR_ADC3EN_BIT 15 +#define RCC_APB2ENR_USART1EN_BIT 14 +#define RCC_APB2ENR_TIM8EN_BIT 13 +#define RCC_APB2ENR_SPI1EN_BIT 12 +#define RCC_APB2ENR_TIM1EN_BIT 11 +#define RCC_APB2ENR_ADC2EN_BIT 10 +#define RCC_APB2ENR_ADC1EN_BIT 9 +#define RCC_APB2ENR_IOPGEN_BIT 8 +#define RCC_APB2ENR_IOPFEN_BIT 7 +#define RCC_APB2ENR_IOPEEN_BIT 6 +#define RCC_APB2ENR_IOPDEN_BIT 5 +#define RCC_APB2ENR_IOPCEN_BIT 4 +#define RCC_APB2ENR_IOPBEN_BIT 3 +#define RCC_APB2ENR_IOPAEN_BIT 2 +#define RCC_APB2ENR_AFIOEN_BIT 0 + +#define RCC_APB2ENR_TIM11EN BIT(RCC_APB2ENR_TIM11EN_BIT) +#define RCC_APB2ENR_TIM10EN BIT(RCC_APB2ENR_TIM10EN_BIT) +#define RCC_APB2ENR_TIM9EN BIT(RCC_APB2ENR_TIM9EN_BIT) +#define RCC_APB2ENR_ADC3EN BIT(RCC_APB2ENR_ADC3EN_BIT) +#define RCC_APB2ENR_USART1EN BIT(RCC_APB2ENR_USART1EN_BIT) +#define RCC_APB2ENR_TIM8EN BIT(RCC_APB2ENR_TIM8EN_BIT) +#define RCC_APB2ENR_SPI1EN BIT(RCC_APB2ENR_SPI1EN_BIT) +#define RCC_APB2ENR_TIM1EN BIT(RCC_APB2ENR_TIM1EN_BIT) +#define RCC_APB2ENR_ADC2EN BIT(RCC_APB2ENR_ADC2EN_BIT) +#define RCC_APB2ENR_ADC1EN BIT(RCC_APB2ENR_ADC1EN_BIT) +#define RCC_APB2ENR_IOPGEN BIT(RCC_APB2ENR_IOPGEN_BIT) +#define RCC_APB2ENR_IOPFEN BIT(RCC_APB2ENR_IOPFEN_BIT) +#define RCC_APB2ENR_IOPEEN BIT(RCC_APB2ENR_IOPEEN_BIT) +#define RCC_APB2ENR_IOPDEN BIT(RCC_APB2ENR_IOPDEN_BIT) +#define RCC_APB2ENR_IOPCEN BIT(RCC_APB2ENR_IOPCEN_BIT) +#define RCC_APB2ENR_IOPBEN BIT(RCC_APB2ENR_IOPBEN_BIT) +#define RCC_APB2ENR_IOPAEN BIT(RCC_APB2ENR_IOPAEN_BIT) +#define RCC_APB2ENR_AFIOEN BIT(RCC_APB2ENR_AFIOEN_BIT) + +/* APB1 peripheral clock enable register */ + +#define RCC_APB1ENR_DACEN_BIT 29 +#define RCC_APB1ENR_BKPEN_BIT 27 +#define RCC_APB1ENR_PWREN_BIT 28 +#define RCC_APB1ENR_CANEN_BIT 25 +#define RCC_APB1ENR_USBEN_BIT 23 +#define RCC_APB1ENR_I2C2EN_BIT 22 +#define RCC_APB1ENR_I2C1EN_BIT 21 +#define RCC_APB1ENR_UART5EN_BIT 20 +#define RCC_APB1ENR_UART4EN_BIT 19 +#define RCC_APB1ENR_UART3EN_BIT 18 +#define RCC_APB1ENR_UART2EN_BIT 17 +#define RCC_APB1ENR_SPI3EN_BIT 15 +#define RCC_APB1ENR_SPI2EN_BIT 14 +#define RCC_APB1ENR_WWDGEN_BIT 11 +#define RCC_APB1ENR_TIM14EN_BIT 8 +#define RCC_APB1ENR_TIM13EN_BIT 7 +#define RCC_APB1ENR_TIM12EN_BIT 6 +#define RCC_APB1ENR_TIM7EN_BIT 5 +#define RCC_APB1ENR_TIM6EN_BIT 4 +#define RCC_APB1ENR_TIM5EN_BIT 3 +#define RCC_APB1ENR_TIM4EN_BIT 2 +#define RCC_APB1ENR_TIM3EN_BIT 1 +#define RCC_APB1ENR_TIM2EN_BIT 0 + +#define RCC_APB1ENR_DACEN BIT(RCC_APB1ENR_DACEN_BIT) +#define RCC_APB1ENR_PWREN BIT(RCC_APB1ENR_PWREN_BIT) +#define RCC_APB1ENR_BKPEN BIT(RCC_APB1ENR_BKPEN_BIT) +#define RCC_APB1ENR_CANEN BIT(RCC_APB1ENR_CANEN_BIT) +#define RCC_APB1ENR_USBEN BIT(RCC_APB1ENR_USBEN_BIT) +#define RCC_APB1ENR_I2C2EN BIT(RCC_APB1ENR_I2C2EN_BIT) +#define RCC_APB1ENR_I2C1EN BIT(RCC_APB1ENR_I2C1EN_BIT) +#define RCC_APB1ENR_UART5EN BIT(RCC_APB1ENR_UART5EN_BIT) +#define RCC_APB1ENR_UART4EN BIT(RCC_APB1ENR_UART4EN_BIT) +#define RCC_APB1ENR_UART3EN BIT(RCC_APB1ENR_UART3EN_BIT) +#define RCC_APB1ENR_UART2EN BIT(RCC_APB1ENR_UART2EN_BIT) +#define RCC_APB1ENR_SPI3EN BIT(RCC_APB1ENR_SPI3EN_BIT) +#define RCC_APB1ENR_SPI2EN BIT(RCC_APB1ENR_SPI2EN_BIT) +#define RCC_APB1ENR_WWDGEN BIT(RCC_APB1ENR_WWDGEN_BIT) +#define RCC_APB1ENR_TIM14EN BIT(RCC_APB1ENR_TIM14EN_BIT) +#define RCC_APB1ENR_TIM13EN BIT(RCC_APB1ENR_TIM13EN_BIT) +#define RCC_APB1ENR_TIM12EN BIT(RCC_APB1ENR_TIM12EN_BIT) +#define RCC_APB1ENR_TIM7EN BIT(RCC_APB1ENR_TIM7EN_BIT) +#define RCC_APB1ENR_TIM6EN BIT(RCC_APB1ENR_TIM6EN_BIT) +#define RCC_APB1ENR_TIM5EN BIT(RCC_APB1ENR_TIM5EN_BIT) +#define RCC_APB1ENR_TIM4EN BIT(RCC_APB1ENR_TIM4EN_BIT) +#define RCC_APB1ENR_TIM3EN BIT(RCC_APB1ENR_TIM3EN_BIT) +#define RCC_APB1ENR_TIM2EN BIT(RCC_APB1ENR_TIM2EN_BIT) + +/* Backup domain control register */ + +#define RCC_BDCR_BDRST_BIT 16 +#define RCC_BDCR_RTCEN_BIT 15 +#define RCC_BDCR_LSEBYP_BIT 2 +#define RCC_BDCR_LSERDY_BIT 1 +#define RCC_BDCR_LSEON_BIT 0 + +#define RCC_BDCR_BDRST BIT(RCC_BDCR_BDRST_BIT) +#define RCC_BDCR_RTCEN BIT(RCC_BDCR_RTCEN_BIT) +#define RCC_BDCR_RTCSEL (0x3 << 8) +#define RCC_BDCR_RTCSEL_LSE (0x1 << 8) +#define RCC_BDCR_RTCSEL_LSI (0x2 << 8) +#define RCC_BDCR_RTCSEL_HSE_DIV_128 (0x3 << 8) +#define RCC_BDCR_LSEBYP BIT(RCC_BDCR_LSEBYP_BIT) +#define RCC_BDCR_LSERDY BIT(RCC_BDCR_LSERDY_BIT) +#define RCC_BDCR_LSEON BIT(RCC_BDCR_LSEON_BIT) + +/* Control/status register */ + +#define RCC_CSR_LPWRRSTF_BIT 31 +#define RCC_CSR_WWDGRSTF_BIT 30 +#define RCC_CSR_IWDGRSTF_BIT 29 +#define RCC_CSR_SFTRSTF_BIT 28 +#define RCC_CSR_PORRSTF_BIT 27 +#define RCC_CSR_PINRSTF_BIT 26 +#define RCC_CSR_RMVF_BIT 25 +#define RCC_CSR_LSIRDY_BIT 1 +#define RCC_CSR_LSION_BIT 0 + +#define RCC_CSR_LPWRRSTF BIT(RCC_CSR_LPWRRSTF_BIT) +#define RCC_CSR_WWDGRSTF BIT(RCC_CSR_WWDGRSTF_BIT) +#define RCC_CSR_IWDGRSTF BIT(RCC_CSR_IWDGRSTF_BIT) +#define RCC_CSR_SFTRSTF BIT(RCC_CSR_SFTRSTF_BIT) +#define RCC_CSR_PORRSTF BIT(RCC_CSR_PORRSTF_BIT) +#define RCC_CSR_PINRSTF BIT(RCC_CSR_PINRSTF_BIT) +#define RCC_CSR_RMVF BIT(RCC_CSR_RMVF_BIT) +#define RCC_CSR_LSIRDY BIT(RCC_CSR_LSIRDY_BIT) +#define RCC_CSR_LSION BIT(RCC_CSR_LSION_BIT) + +/** + * Identifies bus and clock line for a device + */ +typedef enum { + RCC_SRAM, + RCC_GPIOA, + RCC_GPIOB, + RCC_GPIOC, + RCC_GPIOD, + RCC_AFIO, + RCC_ADC1, + RCC_ADC2, + RCC_USART1, + RCC_USART2, + RCC_USART3, + RCC_TIMER1, + RCC_TIMER2, + RCC_TIMER3, + RCC_TIMER4, + RCC_SPI1, + RCC_SPI2, + RCC_DMA1, + RCC_PWR, + RCC_BKP, + RCC_CAN, + RCC_USB, + RCC_I2C1, + RCC_I2C2, + RCC_CRC, + RCC_WWDG, + RCC_FLITF, +#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + RCC_SDIO, + RCC_FSMC, + RCC_GPIOE, + RCC_GPIOF, + RCC_GPIOG, + RCC_ADC3, + RCC_UART4, + RCC_UART5, + RCC_TIMER5, + RCC_TIMER6, + RCC_TIMER7, + RCC_TIMER8, + RCC_DAC, + RCC_DMA2, + RCC_SPI3, +#endif +#ifdef STM32_XL_DENSITY + RCC_TIMER9, + RCC_TIMER10, + RCC_TIMER11, + RCC_TIMER12, + RCC_TIMER13, + RCC_TIMER14, +#endif +} rcc_clk_id; + +/* SYSCLK source */ #define RCC_CLKSRC_HSI (0x0) #define RCC_CLKSRC_HSE (0x1) #define RCC_CLKSRC_PLL (0x2) -/* pll entry clock source */ -#define RCC_PLLSRC_HSE (0x1 << 16) -#define RCC_PLLSRC_HSI_DIV_2 (0x0 << 16) - -/* adc prescaler dividers */ +/* ADC prescaler dividers */ #define RCC_ADCPRE_PCLK_DIV_2 (0x0 << 14) #define RCC_ADCPRE_PCLK_DIV_4 (0x1 << 14) #define RCC_ADCPRE_PCLK_DIV_6 (0x2 << 14) #define RCC_ADCPRE_PCLK_DIV_8 (0x3 << 14) -/* apb1 prescaler dividers */ +/* APB1 prescaler dividers */ #define RCC_APB1_HCLK_DIV_1 (0x0 << 8) #define RCC_APB1_HCLK_DIV_2 (0x4 << 8) #define RCC_APB1_HCLK_DIV_4 (0x5 << 8) #define RCC_APB1_HCLK_DIV_8 (0x6 << 8) #define RCC_APB1_HCLK_DIV_16 (0x7 << 8) -/* apb2 prescaler dividers */ +/* APB2 prescaler dividers */ #define RCC_APB2_HCLK_DIV_1 (0x0 << 11) #define RCC_APB2_HCLK_DIV_2 (0x4 << 11) #define RCC_APB2_HCLK_DIV_4 (0x5 << 11) #define RCC_APB2_HCLK_DIV_8 (0x6 << 11) #define RCC_APB2_HCLK_DIV_16 (0x7 << 11) -/* ahb prescaler dividers */ +/* AHB prescaler dividers */ #define RCC_AHB_SYSCLK_DIV_1 (0x0 << 4) #define RCC_AHB_SYSCLK_DIV_2 (0x8 << 4) #define RCC_AHB_SYSCLK_DIV_4 (0x9 << 4) @@ -119,75 +492,19 @@ extern "C"{ #define RCC_AHB_SYSCLK_DIV_256 (0xE << 4) #define RCC_AHB_SYSCLK_DIV_512 (0xF << 4) -/* pll multipliers */ -#define RCC_PLLMUL_2 (0x0 << 18) -#define RCC_PLLMUL_3 (0x1 << 18) -#define RCC_PLLMUL_4 (0x2 << 18) -#define RCC_PLLMUL_5 (0x3 << 18) -#define RCC_PLLMUL_6 (0x4 << 18) -#define RCC_PLLMUL_7 (0x5 << 18) -#define RCC_PLLMUL_8 (0x6 << 18) -#define RCC_PLLMUL_9 (0x7 << 18) -#define RCC_PLLMUL_10 (0x8 << 18) -#define RCC_PLLMUL_11 (0x9 << 18) -#define RCC_PLLMUL_12 (0xA << 18) -#define RCC_PLLMUL_13 (0xB << 18) -#define RCC_PLLMUL_14 (0xC << 18) -#define RCC_PLLMUL_15 (0xD << 18) -#define RCC_PLLMUL_16 (0xE << 18) - - -/* prescalers */ -enum { +/* Prescalers */ +typedef enum rcc_prescaler { RCC_PRESCALER_AHB, RCC_PRESCALER_APB1, RCC_PRESCALER_APB2, RCC_PRESCALER_USB, RCC_PRESCALER_ADC -}; - -/* - * Identifies bus and clock line for a device - */ -typedef enum { - RCC_GPIOA, - RCC_GPIOB, - RCC_GPIOC, - RCC_GPIOD, - RCC_GPIOE, // High-density devices only (Maple Native) - RCC_GPIOF, // High-density devices only (Maple Native) - RCC_GPIOG, // High-density devices only (Maple Native) - RCC_AFIO, - RCC_ADC1, - RCC_ADC2, - RCC_ADC3, - RCC_USART1, - RCC_USART2, - RCC_USART3, - RCC_UART4, // High-density devices only (Maple Native) - RCC_UART5, // High-density devices only (Maple Native) - RCC_TIMER1, - RCC_TIMER2, - RCC_TIMER3, - RCC_TIMER4, - RCC_TIMER5, // High-density devices only (Maple Native) - RCC_TIMER6, // High-density devices only (Maple Native) - RCC_TIMER7, // High-density devices only (Maple Native) - RCC_TIMER8, // High-density devices only (Maple Native) - RCC_SPI1, - RCC_SPI2, - RCC_FSMC, // High-density devices only (Maple Native) - RCC_DAC, // High-density devices only (Maple Native) - RCC_DMA1, - RCC_DMA2, // High-density devices only (Maple Native) - RCC_PWR, - RCC_BKP, -} rcc_clk_id; +} rcc_prescaler; void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul); void rcc_clk_enable(rcc_clk_id device); void rcc_reset_dev(rcc_clk_id device); -void rcc_set_prescaler(uint32 prescaler, uint32 divider); +void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider); #ifdef __cplusplus } // extern "C" diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 9276f36..440218b 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -304,7 +304,7 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D98/PG5 */ {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, /* D99/PD10 */ - {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD} + {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD} }; #elif defined(BOARD_maple_mini) diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index f2fb89b..6967489 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -52,7 +52,7 @@ void init(void) { #endif /* initialize clocks */ - rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); + rcc_clk_init(RCC_CLKSRC_PLL, RCC_CFGR_PLLSRC_HSE, RCC_CFGR_PLLMUL_9); rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); -- cgit v1.2.3 From 334de50c49317f281d87f44e7b9278e08af19254 Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Mon, 14 Mar 2011 18:37:56 -0400 Subject: Add rudimentary error handling for nack condition --- libmaple/i2c.c | 51 ++++++++++++++++++---------------------- libmaple/i2c.h | 43 ++++++++++++++++++++++++--------- main.cpp | 73 +++++++++++++++++++++++++++++++++++++++------------------ wirish/wirish.c | 24 +++++++++---------- 4 files changed, 117 insertions(+), 74 deletions(-) (limited to 'wirish') diff --git a/libmaple/i2c.c b/libmaple/i2c.c index 3e948f6..8bd252c 100644 --- a/libmaple/i2c.c +++ b/libmaple/i2c.c @@ -23,9 +23,7 @@ * ****************************************************************************/ /** - * @brief - * TODO: Rejigger hard fault handler and error throbs to turn off all - * interrupts and jump to error throb to reenable usb bootloader + * @brief */ #include "libmaple.h" @@ -36,12 +34,6 @@ #include "i2c.h" #include "string.h" -/* 2/17 Started 10pm-4am - * 2/19 Started 7pm-2am - * 2/20 Started 7pm-7pm - * 2/23 Started 8pm-8am - * 3/9 Started 11pm */ - static inline int32 wait_for_state_change(i2c_dev *dev, i2c_state state); static i2c_dev i2c_dev1 = { @@ -57,22 +49,18 @@ static i2c_dev i2c_dev1 = { i2c_dev* const I2C1 = &i2c_dev1; -/** - * @brief IRQ handler for i2c master. Handles transmission/reception. - * @param dev i2c device - */ - struct crumb { uint32 event; uint32 sr1; uint32 sr2; }; -static struct crumb crumbs[100]; +#define NR_CRUMBS 128 +static struct crumb crumbs[NR_CRUMBS]; static uint32 cur_crumb = 0; static inline void leave_big_crumb(uint32 event, uint32 sr1, uint32 sr2) { - if (cur_crumb < 100) { + if (cur_crumb < NR_CRUMBS) { struct crumb *crumb = &crumbs[cur_crumb++]; crumb->event = event; crumb->sr1 = sr1; @@ -93,8 +81,13 @@ enum { RXNE_START_SENT = 10, RXNE_STOP_SENT = 11, RXNE_DONE = 12, + ERROR_ENTRY = 13, }; +/** + * @brief IRQ handler for i2c master. Handles transmission/reception. + * @param dev i2c device + */ static void i2c_irq_handler(i2c_dev *dev) { i2c_msg *msg = dev->msg; @@ -117,6 +110,7 @@ static void i2c_irq_handler(i2c_dev *dev) { if (read) { i2c_enable_ack(dev); } + i2c_send_slave_addr(dev, msg->addr, read); sr1 = sr2 = 0; } @@ -133,8 +127,7 @@ static void i2c_irq_handler(i2c_dev *dev) { if (read) { if (msg->length == 1) { i2c_disable_ack(dev); - dev->msgs_left--; - if (dev->msgs_left) { + if (dev->msgs_left > 1) { i2c_start_condition(dev); leave_big_crumb(RX_ADDR_START, 0, 0); } else { @@ -197,9 +190,7 @@ static void i2c_irq_handler(i2c_dev *dev) { dev->msg++; } else { i2c_stop_condition(dev); -// while (dev->regs->CR1 & I2C_CR1_STOP) { -// ; -// } + /* * Turn off event interrupts to keep BTF from firing until the end * of the stop condition. Why on earth they didn't have a start/stop @@ -253,7 +244,13 @@ void __irq_i2c1_ev(void) { } static void i2c_irq_error_handler(i2c_dev *dev) { - __error(); + uint32 sr1 = dev->regs->SR1; + uint32 sr2 = dev->regs->SR2; + leave_big_crumb(ERROR_ENTRY, sr1, sr2); + + i2c_stop_condition(dev); + i2c_disable_irq(dev, I2C_IRQ_BUFFER | I2C_IRQ_EVENT | I2C_IRQ_ERROR); + dev->state = I2C_STATE_ERROR; } void __irq_i2c1_er(void) { @@ -330,7 +327,8 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { /* Enable event and buffer interrupts */ nvic_irq_enable(dev->ev_nvic_line); - i2c_enable_irq(dev, I2C_IRQ_EVENT | I2C_IRQ_BUFFER); + nvic_irq_enable(dev->er_nvic_line); + i2c_enable_irq(dev, I2C_IRQ_EVENT | I2C_IRQ_BUFFER | I2C_IRQ_ERROR); /* * Important STM32 Errata: @@ -360,6 +358,7 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) { * been initialized to priority level 16. See nvic_init(). */ nvic_irq_set_priority(dev->ev_nvic_line, 0); + nvic_irq_set_priority(dev->er_nvic_line, 0); /* Make it go! */ i2c_peripheral_enable(dev); @@ -372,15 +371,11 @@ int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num) { dev->msg = msgs; dev->msgs_left = num; - memset(crumbs, 0, sizeof crumbs); - - dev->regs->CR2 |= I2C_CR2_ITEVTEN; - - /* Is this necessary? */ while (dev->regs->SR2 & I2C_SR2_BUSY) ; dev->state = I2C_STATE_BUSY; + i2c_enable_irq(dev, I2C_IRQ_EVENT); i2c_start_condition(dev); rc = wait_for_state_change(dev, I2C_STATE_XFER_DONE); diff --git a/libmaple/i2c.h b/libmaple/i2c.h index be05615..a9e2c7b 100644 --- a/libmaple/i2c.h +++ b/libmaple/i2c.h @@ -136,17 +136,13 @@ extern "C" { void i2c_master_enable(i2c_dev *dev, uint32 flags); int32 i2c_master_xfer(i2c_dev *dev, i2c_msg *msgs, uint16 num); -static inline void i2c_write(i2c_dev *dev, uint8 byte) { - dev->regs->DR = byte; -} - /* * Low level register twiddling functions */ /** * @brief turn on an i2c peripheral - * @param map i2c peripheral register base + * @param dev i2c device */ static inline void i2c_peripheral_enable(i2c_dev *dev) { dev->regs->CR1 |= I2C_CR1_PE; @@ -154,15 +150,25 @@ static inline void i2c_peripheral_enable(i2c_dev *dev) { /** * @brief turn off an i2c peripheral - * @param map i2c peripheral register base + * @param dev i2c device */ static inline void i2c_peripheral_disable(i2c_dev *dev) { dev->regs->CR1 &= ~I2C_CR1_PE; } +/** + * @brief Fill transmit register + * @param dev i2c device + * @param byte byte to write + */ +static inline void i2c_write(i2c_dev *dev, uint8 byte) { + dev->regs->DR = byte; +} + + /** * @brief Set input clock frequency, in mhz - * @param device to configure + * @param dev i2c * @param freq frequency in megahertz (2-36) */ static inline void i2c_set_input_clk(i2c_dev *dev, uint32 freq) { @@ -172,6 +178,13 @@ static inline void i2c_set_input_clk(i2c_dev *dev, uint32 freq) { dev->regs->CR2 = freq; } + +/** + * @brief Set i2c clock control register. See RM008 + * @param dev i2c device + * @return + * @sideeffect + */ static inline void i2c_set_clk_control(i2c_dev *dev, uint32 val) { uint32 ccr = dev->regs->CCR; ccr &= ~I2C_CCR_CCR; @@ -195,15 +208,23 @@ static inline void i2c_set_trise(i2c_dev *dev, uint32 trise) { dev->regs->TRISE = trise; } -extern void toggle(void); static inline void i2c_start_condition(i2c_dev *dev) { - uint32 cr1 = dev->regs->CR1; -// if (cr1 & (I2C_CR1_START | I2C_CR1_STOP | I2C_CR1_PEC)) { -// } + uint32 cr1; + while ((cr1 = dev->regs->CR1) & (I2C_CR1_START | + I2C_CR1_STOP | + I2C_CR1_PEC)) { + ; + } dev->regs->CR1 |= I2C_CR1_START; } static inline void i2c_stop_condition(i2c_dev *dev) { + uint32 cr1; + while ((cr1 = dev->regs->CR1) & (I2C_CR1_START | + I2C_CR1_STOP | + I2C_CR1_PEC)) { + ; + } dev->regs->CR1 |= I2C_CR1_STOP; } diff --git a/main.cpp b/main.cpp index 7771fa7..db310c0 100644 --- a/main.cpp +++ b/main.cpp @@ -1,12 +1,13 @@ // Sample i2c master example for development i2c branch. Writes 0-63 to // addresses 0-63 on a 24LC256 EEPROM, then reads them back. +#include #include "wirish.h" #include "i2c.h" static const uint8 slave_address = 0b1010001; -#define NR_ELEMENTS 4 +#define NR_ELEMENTS 64 uint8 buf0[NR_ELEMENTS + 2] = {0x0, 0x0}; uint8 buf1[] = {0x0, 0x0}; uint8 buf2[NR_ELEMENTS]; @@ -19,12 +20,15 @@ void toggle(void) { } void setup() { + uint32 bytes = 1; uint32 i; + int32 rc = -1; pinMode(BOARD_LED_PIN, OUTPUT); - pinMode(2, OUTPUT); Serial2.begin(9600); Serial2.println("Hello!"); + + pinMode(2, OUTPUT); digitalWrite(2, LOW); for (i = 2; i < sizeof buf0; i++) { @@ -33,31 +37,54 @@ void setup() { i2c_master_enable(I2C1, 0); - /* Write some bytes */ - msgs[0].addr = slave_address; - msgs[0].flags = 0; - msgs[0].length = sizeof buf0; - msgs[0].data = buf0; - i2c_master_xfer(I2C1, msgs, 1); - delay(5); - + while (bytes < 64) { + Serial2.print("Writing "); + Serial2.print(bytes); + Serial2.print(" bytes..."); + + /* Write test pattern */ + msgs[0].addr = slave_address; + msgs[0].flags = 0; + msgs[0].length = 2+ bytes; + msgs[0].data = buf0; + i2c_master_xfer(I2C1, msgs, 1); + delay(5); + + /* Read it back */ + msgs[1].addr = slave_address; + msgs[1].flags = 0; + msgs[1].length = 2; + msgs[1].data = buf1; + /* Repeated start condition */ + msgs[2].addr = slave_address; + msgs[2].flags = I2C_MSG_READ; + msgs[2].length = bytes; + msgs[2].data = buf2; + i2c_master_xfer(I2C1, msgs + 1, 2); + + /* Compare */ + rc = memcmp(&buf0[2], buf2, bytes); + if (rc == 0) { + Serial2.println("good!"); + } else { + Serial2.println("failed!"); + } + + delay(5); + bytes++; + } } +int32 rc; + void loop() { - delay(100); toggleLED(); - /* Write slave address to read */ - msgs[1].addr = slave_address; - msgs[1].flags = 0; - msgs[1].length = 2; - msgs[1].data = buf1; - - /* Repeated start condition, then read NR_ELEMENTS bytes back */ - msgs[2].addr = slave_address; - msgs[2].flags = I2C_MSG_READ; - msgs[2].length = sizeof buf2; - msgs[2].data = buf2; - i2c_master_xfer(I2C1, msgs + 1, 2); + delay(100); + rc = i2c_master_xfer(I2C1, msgs + 1, 2); + if (rc < 0) { + Serial2.println("Failed transfer!"); + i2c_master_enable(I2C1, 0); + } } // Force init to be called *first*, i.e. before static object allocation. diff --git a/wirish/wirish.c b/wirish/wirish.c index 4c84d26..2b128f1 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -63,18 +63,18 @@ void init(void) { /* Initialize the ADC for slow conversions, to allow for high impedance inputs. */ - adc_init(ADC1, 0); - adc_set_sample_rate(ADC1, ADC_SMPR_55_5); - - timer_init(TIMER1, 1); - timer_init(TIMER2, 1); - timer_init(TIMER3, 1); - timer_init(TIMER4, 1); -#ifdef STM32_HIGH_DENSITY - timer_init(TIMER5, 1); - timer_init(TIMER8, 1); -#endif - setupUSB(); +// adc_init(ADC1, 0); +// adc_set_sample_rate(ADC1, ADC_SMPR_55_5); +// +// timer_init(TIMER1, 1); +// timer_init(TIMER2, 1); +// timer_init(TIMER3, 1); +// timer_init(TIMER4, 1); +//#ifdef STM32_HIGH_DENSITY +// timer_init(TIMER5, 1); +// timer_init(TIMER8, 1); +//#endif +// setupUSB(); /* include the board-specific init macro */ BOARD_INIT; -- cgit v1.2.3 From c73306508820705eef4f2cb9f8542acdba599cd8 Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Tue, 15 Mar 2011 19:46:47 -0400 Subject: Reenable other peripherals. --- wirish/wirish.c | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) (limited to 'wirish') diff --git a/wirish/wirish.c b/wirish/wirish.c index 2b128f1..4c84d26 100644 --- a/wirish/wirish.c +++ b/wirish/wirish.c @@ -63,18 +63,18 @@ void init(void) { /* Initialize the ADC for slow conversions, to allow for high impedance inputs. */ -// adc_init(ADC1, 0); -// adc_set_sample_rate(ADC1, ADC_SMPR_55_5); -// -// timer_init(TIMER1, 1); -// timer_init(TIMER2, 1); -// timer_init(TIMER3, 1); -// timer_init(TIMER4, 1); -//#ifdef STM32_HIGH_DENSITY -// timer_init(TIMER5, 1); -// timer_init(TIMER8, 1); -//#endif -// setupUSB(); + adc_init(ADC1, 0); + adc_set_sample_rate(ADC1, ADC_SMPR_55_5); + + timer_init(TIMER1, 1); + timer_init(TIMER2, 1); + timer_init(TIMER3, 1); + timer_init(TIMER4, 1); +#ifdef STM32_HIGH_DENSITY + timer_init(TIMER5, 1); + timer_init(TIMER8, 1); +#endif + setupUSB(); /* include the board-specific init macro */ BOARD_INIT; -- cgit v1.2.3 From 4862d1eae5813e278cfbb1d5e0a040010b92eb3f Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 16 Mar 2011 17:37:21 -0400 Subject: Maple RET6 edition support --- Makefile | 7 ++++ examples/test-session.cpp | 9 ++--- libmaple/libmaple.h | 7 +++- libmaple/pwr.c | 2 +- libmaple/rules.mk | 1 + libmaple/usb/usb_config.h | 10 ++--- support/ld/maple_RET6/flash.ld | 18 +++++++++ support/ld/maple_RET6/jtag.ld | 17 ++++++++ support/ld/maple_RET6/ram.ld | 18 +++++++++ support/ld/maple_native/ram.ld | 1 - support/scripts/copy-to-ide | 18 ++++++--- wirish/boards.cpp | 89 ++++++++++++++++++++++++++++++++++++++++++ wirish/boards.h | 15 +++++++ wirish/wirish.cpp | 2 +- 14 files changed, 194 insertions(+), 20 deletions(-) create mode 100644 support/ld/maple_RET6/flash.ld create mode 100644 support/ld/maple_RET6/jtag.ld create mode 100644 support/ld/maple_RET6/ram.ld (limited to 'wirish') diff --git a/Makefile b/Makefile index 3804421..d31c9ed 100644 --- a/Makefile +++ b/Makefile @@ -31,6 +31,13 @@ ifeq ($(BOARD), maple_mini) ERROR_LED_PIN := 1 DENSITY := STM32_MEDIUM_DENSITY endif +ifeq ($(BOARD), maple_RET6) + MCU := STM32F103RE + PRODUCT_ID := 0003 + ERROR_LED_PORT := GPIOA + ERROR_LED_PIN := 5 + DENSITY := STM32_HIGH_DENSITY +endif # Useful paths ifeq ($(LIB_MAPLE_HOME),) diff --git a/examples/test-session.cpp b/examples/test-session.cpp index ea631ca..a147e06 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -20,7 +20,7 @@ int rate = 0; -#if defined(BOARD_maple) +#if defined(BOARD_maple) || defined(BOARD_maple_RET6) const uint8 pwm_pins[] = {0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 25, 27, 28}; const uint8 adc_pins[] = @@ -617,15 +617,14 @@ void init_all_timers(uint16 prescale) { timer_init(TIMER4, prescale); #ifdef STM32_HIGH_DENSITY timer_init(TIMER5, prescale); - timer_init(TIMER6, prescale); - timer_init(TIMER7, prescale); + // timer_init(TIMER6, prescale); + // timer_init(TIMER7, prescale); timer_init(TIMER8, prescale); #endif } - // Force init to be called *first*, i.e. before static object allocation. -// Otherwise, statically allocated object that need libmaple may fail. +// Otherwise, statically allocated objects that need libmaple may fail. __attribute__(( constructor )) void premain() { init(); } diff --git a/libmaple/libmaple.h b/libmaple/libmaple.h index 0bbd34e..7814730 100644 --- a/libmaple/libmaple.h +++ b/libmaple/libmaple.h @@ -56,7 +56,6 @@ /* e.g., LeafLabs Maple Native */ #define NR_GPIO_PORTS 7 - #define SRAM_SIZE 0x10000 #elif defined(MCU_STM32F103CB) @@ -69,6 +68,12 @@ #define SRAM_SIZE 0x5000 +#elif defined(MCU_STM32F103RE) + /* e.g., LeafLabs Maple RET6 edition */ + + #define NR_GPIO_PORTS 4 + #define SRAM_SIZE 0x10000 + #else #error "No MCU type specified. Add something like -DMCU_STM32F103RB " \ diff --git a/libmaple/pwr.c b/libmaple/pwr.c index b43193e..d63a92d 100644 --- a/libmaple/pwr.c +++ b/libmaple/pwr.c @@ -28,7 +28,7 @@ #include "rcc.h" pwr_dev pwr = { - .regs = PWR_BASE; + .regs = PWR_BASE, }; const pwr_dev *PWR = &pwr; diff --git a/libmaple/rules.mk b/libmaple/rules.mk index b87595d..b264b96 100644 --- a/libmaple/rules.mk +++ b/libmaple/rules.mk @@ -22,6 +22,7 @@ cSRCS_$(d) := adc.c \ gpio.c \ iwdg.c \ nvic.c \ + pwr.c \ rcc.c \ spi.c \ syscalls.c \ diff --git a/libmaple/usb/usb_config.h b/libmaple/usb/usb_config.h index 9003da9..0860b90 100644 --- a/libmaple/usb/usb_config.h +++ b/libmaple/usb/usb_config.h @@ -28,7 +28,7 @@ #define RESET_DELAY (100) #define USB_CONFIG_MAX_POWER (100 >> 1) -#if defined(BOARD_maple) +#if defined(BOARD_maple) || defined(BOARD_maple_RET6) /* USB Identifier numbers */ #define VCOM_ID_PRODUCT 0x0004 @@ -37,13 +37,13 @@ #elif defined(BOARD_maple_mini) - #define VCOM_ID_PRODUCT 0x0005 + #define VCOM_ID_PRODUCT 0x0004 #define USB_DISC_DEV GPIOB #define USB_DISC_PIN 9 #elif defined(BOARD_maple_native) - #define VCOM_ID_PRODUCT 0x0006 + #define VCOM_ID_PRODUCT 0x0004 #define USB_DISC_DEV GPIOB #define USB_DISC_PIN 8 @@ -51,8 +51,8 @@ #error ("Sorry! the USB stack relies on LeafLabs board-specific " \ "configuration right now. If you want, you can pretend you're one " \ - "of our boards; i.e., #define BOARD_maple, BOARD_maple_mini, or " \ - "BOARD_maple_native according to what matches your MCU best. " \ + "of our boards; i.e., #define BOARD_maple, BOARD_maple_mini, or " \ + "BOARD_maple_native according to what matches your MCU best. " \ "You should also take a look at libmaple/usb/descriptors.c; we make " \ "some assumptions there that you probably won't like.") diff --git a/support/ld/maple_RET6/flash.ld b/support/ld/maple_RET6/flash.ld new file mode 100644 index 0000000..2a4f0c7 --- /dev/null +++ b/support/ld/maple_RET6/flash.ld @@ -0,0 +1,18 @@ +/* + * STM32F103RET6 high density chip linker script for use with Maple + * bootloader. Loads to Flash. + */ + +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 61K + rom (rx) : ORIGIN = 0x08005000, LENGTH = 492K +} + +GROUP(libcs3_stm32_high_density.a) + +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); + +INCLUDE common_rom.inc diff --git a/support/ld/maple_RET6/jtag.ld b/support/ld/maple_RET6/jtag.ld new file mode 100644 index 0000000..88f45e0 --- /dev/null +++ b/support/ld/maple_RET6/jtag.ld @@ -0,0 +1,17 @@ +/* + * STM32F103RET6 high density bare metal linker script. + */ + +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K +} + +GROUP(libcs3_stm32_high_density.a) + +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); + +INCLUDE common_rom.inc diff --git a/support/ld/maple_RET6/ram.ld b/support/ld/maple_RET6/ram.ld new file mode 100644 index 0000000..f09acd9 --- /dev/null +++ b/support/ld/maple_RET6/ram.ld @@ -0,0 +1,18 @@ +/* + * STM32F103RET6 high density chip linker script for use with Maple + * bootloader. Loads to RAM. + */ + +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 61K + rom (rx) : ORIGIN = 0x08005000, LENGTH = 0K +} + +GROUP(libcs3_stm32_high_density.a) + +REGION_ALIAS("REGION_TEXT", ram); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); + +INCLUDE common_ram.inc diff --git a/support/ld/maple_native/ram.ld b/support/ld/maple_native/ram.ld index 22c09cd..d5bd3b0 100644 --- a/support/ld/maple_native/ram.ld +++ b/support/ld/maple_native/ram.ld @@ -19,4 +19,3 @@ REGION_ALIAS("REGION_DATA", ram); REGION_ALIAS("REGION_BSS", ram); INCLUDE common_ram.inc - diff --git a/support/scripts/copy-to-ide b/support/scripts/copy-to-ide index 301126d..5254974 100755 --- a/support/scripts/copy-to-ide +++ b/support/scripts/copy-to-ide @@ -1,7 +1,8 @@ #!/bin/sh -# This hack copies the necessary library files into the Maple IDE -# repository. +# This hack copies libmaple's source, linker scripts, and built +# documentation into the Maple IDE repository (which is expected as +# its first argument). DEST=$1 @@ -18,14 +19,18 @@ LMAPLE_SRC="LICENSE ./libmaple/usb/usb_lib/*.h ./libmaple/usb/usb_lib/*.c ./wirish/*.h - ./wirish/*.c ./wirish/main.cxx ./wirish/*.cpp ./wirish/comm/*.cpp ./wirish/comm/*.h + ./support/ld/common_ram.inc + ./support/ld/common_rom.inc + ./support/ld/libcs3_stm32_high_density.a + ./support/ld/libcs3_stm32_med_density.a ./support/ld/maple + ./support/ld/maple_mini ./support/ld/maple_native - ./support/ld/libcs3-lanchon-stm32.a + ./support/ld/maple_RET6 ./support/ld/names.inc" LMAPLE_DOCS=./docs @@ -40,7 +45,8 @@ fi # source echo Copying libmaple source -rm -rf $DEST_CORES/*.c $DEST_CORES/*.cpp $DEST_CORES/*.h $DEST_CORES/*.cxx $DEST_CORES/*.inc $DEST_CORES/*.a $DEST_CORES/*.S $DEST_CORES/maple $DEST_CORES/maple_native +rm -rf $DEST_CORES/*.c $DEST_CORES/*.cpp $DEST_CORES/*.h $DEST_CORES/*.cxx $DEST_CORES/*.S +rm -rf $DEST_CORES/*.inc $DEST_CORES/*.a $DEST_CORES/maple $DEST_CORES/maple_* cp -R $LMAPLE_SRC $DEST_CORES echo Copying over libraries @@ -51,7 +57,7 @@ echo Deleting old reference directory contents rm -rf $DEST_REF/* echo Rebuilding documentation -( cd $LMAPLE_DOCS; doxygen && make clean 2>/dev/null 1>/dev/null && make html ) +( cd $LMAPLE_DOCS; doxygen >/dev/null 2>&1 && make clean >/dev/null 2>&1 && make html ) echo Copying over documentation cp -R $LMAPLE_DOCS_BUILD/* $DEST_REF diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 440218b..66f008f 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -380,6 +380,95 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = { {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, }; +#elif defined(BOARD_maple_RET6) + +PinMapping PIN_MAP[NR_GPIO_PINS] = { + /* D0/PA3 */ + {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, + /* D1/PA2 */ + {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, + /* D2/PA0 */ + {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, + /* D3/PA1 */ + {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, + /* D4/PB5 */ + {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D5/PB6 */ + {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, + /* D6/PA8 */ + {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, + /* D7/PA9 */ + {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, + /* D8/PA10 */ + {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, + /* D9/PB7 */ + {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, + /* D10/PA4 */ + {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D11/PA7 */ + {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, + /* D12/PA6 */ + {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, + /* D13/PA5 */ + {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, + /* D14/PB8 */ + {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, + + /* Little header */ + + /* D15/PC0 */ + {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D16/PC1 */ + {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D17/PC2 */ + {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D18/PC3 */ + {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D19/PC4 */ + {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D20/PC5 */ + {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + + /* External header */ + + /* D21/PC13 */ + {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D22/PC14 */ + {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D23/PC15 */ + {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D24/PB9 */ + {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, + /* D25/PD2 */ + {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, + /* D26/PC10 */ + {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + /* D27/PB0 */ + {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, + /* D28/PB1 */ + {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, + /* D29/PB10 */ + {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D30/PB11 */ + {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D31/PB12 */ + {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D32/PB13 */ + {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D33/PB14 */ + {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D34/PB15 */ + {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, + /* D35/PC6 */ + {GPIOC, 6, ADCx, TIMER8_CH1_CCR, TIMER8, 1, AFIO_EXTI_PC}, + /* D36/PC7 */ + {GPIOC, 7, ADCx, TIMER8_CH1_CCR, TIMER8, 2, AFIO_EXTI_PC}, + /* D37/PC8 */ + {GPIOC, 8, ADCx, TIMER8_CH1_CCR, TIMER8, 3, AFIO_EXTI_PC}, + /* D38/PC9 (BUT) */ + {GPIOC, 9, ADCx, TIMER8_CH1_CCR, TIMER8, 4, AFIO_EXTI_PC} +}; + #else #error "Board type has not been selected correctly." diff --git a/wirish/boards.h b/wirish/boards.h index 2941127..94566fa 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -113,6 +113,21 @@ extern PinMapping PIN_MAP[]; afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); \ } while (0) +#elif defined(BOARD_maple_RET6) + + #define CYCLES_PER_MICROSECOND 72 + #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ + + #define BOARD_BUTTON_PIN 38 + #define BOARD_LED_PIN 13 + + /* Total number of GPIO pins that are broken out to headers and + intended for general use. */ + #define NR_GPIO_PINS 39 + + #define BOARD_INIT do { \ + } while(0) + #else #error "Board type has not been selected correctly." diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index 6967489..6d77bc8 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -47,7 +47,7 @@ void init(void) { flash_enable_prefetch(); flash_set_latency(FLASH_WAIT_STATE_2); -#ifdef STM32_HIGH_DENSITY +#ifdef BOARD_maple_native fsmc_native_sram_init(); #endif -- cgit v1.2.3 From 9cea4517c1db13a6f16eb3854c18c7fc02cbdeda Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 15 Mar 2011 20:47:53 -0400 Subject: FSMC refactor; SRAM test code --- examples/fsmc-stress-test.cpp | 216 +++++++++++++++++++++++++++++ examples/test-fsmc.cpp | 208 ++++++++++++++-------------- libmaple/fsmc.c | 53 +------- libmaple/fsmc.h | 308 ++++++++++++++++++++++++++++++++++++------ wirish/native_sram.cpp | 45 ++++++ wirish/native_sram.h | 43 ++++++ wirish/rules.mk | 1 + wirish/wirish.cpp | 3 +- 8 files changed, 684 insertions(+), 193 deletions(-) create mode 100644 examples/fsmc-stress-test.cpp create mode 100644 wirish/native_sram.cpp create mode 100644 wirish/native_sram.h (limited to 'wirish') diff --git a/examples/fsmc-stress-test.cpp b/examples/fsmc-stress-test.cpp new file mode 100644 index 0000000..12e8650 --- /dev/null +++ b/examples/fsmc-stress-test.cpp @@ -0,0 +1,216 @@ +/* + + A low-level stress test of SRAM functionality. Uses slow-ish timing + by default (DATAST = ADDSET = 0xF). + + Copyright 2011 LeafLabs, LLC. + + This code is released into the public domain. + + */ + +#include +#include + +#include "wirish.h" +#include "rcc.h" +#include "fsmc.h" + +// -- SRAM config ------------------------------------------------------------- + +// Timing configuration +#define DATAST 0xF +#define ADDSET 0xF + +// Number of SRAM chips to test +#define N 1 + +// How much of each to test +#define MEM_SIZE 0x3FFF + +// Their start addresses in FSMC bank 1 +__io uint16 *const starts[N] = { + // (__io uint16 *const)FSMC_NOR_PSRAM_REGION1, + // (__io uint16 *const)FSMC_NOR_PSRAM_REGION2, + (__io uint16 *const)FSMC_NOR_PSRAM_REGION3, + // (__io uint16 *const)FSMC_NOR_PSRAM_REGION4, +}; + +// Corresponding FSMC configuration registers +__io uint32 *const bcrs[N] = { + // &FSMC_NOR_PSRAM1_BASE->BCR, + // &FSMC_NOR_PSRAM2_BASE->BCR, + &FSMC_NOR_PSRAM3_BASE->BCR, + // &FSMC_NOR_PSRAM4_BASE->BCR, +}; + +// Corresponding FSMC timing registers +__io uint32 *const btrs[N] = { + // &FSMC_NOR_PSRAM1_BASE->BTR, + // &FSMC_NOR_PSRAM2_BASE->BTR, + &FSMC_NOR_PSRAM3_BASE->BTR, + // &FSMC_NOR_PSRAM4_BASE->BTR, +}; + +// -- Pseudorandom number generation ----------------------------------------- + +const uint32 seed = 0xDEADBEEF; + +uint32 num_rand_calls = 0; + +uint32 rand(long n) { + num_rand_calls++; + return random(n); +} + +// -- Printing ---------------------------------------------------------------- + +// For snprintf() +char snprintf_buf[200]; + +#define ERR(fmt, ...) do { \ + snprintf(snprintf_buf, sizeof snprintf_buf, \ + "ERROR: " fmt " (seed %d, ncalls %d, line %d)", \ + __VA_ARGS__, seed, num_rand_calls, __LINE__); \ + Serial1.println(snprintf_buf); \ + } while (0) + +// -- setup()/loop() ---------------------------------------------------------- + +void setup() { + fsmc_sram_init_gpios(); + rcc_clk_enable(RCC_FSMC); + + for (int i = 0; i < N; i++) { + *bcrs[i] = (FSMC_BCR_WREN | + FSMC_BCR_MTYP_SRAM | + FSMC_BCR_MWID_16BITS | + FSMC_BCR_MBKEN); + *btrs[i] = (DATAST << 8) | ADDSET; + } + + Serial1.begin(115200); + randomSeed(seed); +} + +// stress_test() and simple_roundtrip() are the available test routines +bool stress_test(void); +bool simple_roundtrip(void); + +void loop() { + uint32 count = 0; + bool ok = true; + bool (*test)(void) = stress_test; + + while (true) { + count++; + bool result = test(); + ok = ok && result; + if (ok) { + snprintf(snprintf_buf, sizeof snprintf_buf, + "everything ok so far, timestamp %d ms", millis()); + Serial1.println(snprintf_buf); + } + } +} + +// -- Test routines ----------------------------------------------------------- + +bool random_trips(); +bool sequential_trips(); + +bool stress_test(void) { + static int i = 0; + i = !i; + + switch (i) { + case 0: + return random_trips(); + default: + return sequential_trips(); + } +} + +bool simple_roundtrip(void) { + uint16 wval = 0xAB; + + for (int i = 0; i < N; i++) { + __io uint16 *addr = starts[i] + 4; + snprintf(snprintf_buf, sizeof snprintf_buf, "round-trip 0x%x at %p", + wval, addr); + Serial1.println(snprintf_buf); + + *addr = wval; + uint16 rval = *addr; + + if (rval != wval) { + ERR("wrote 0x%x, read 0x%x, timestamp %d", wval, rval, millis()); + return false; + } else { + snprintf(snprintf_buf, sizeof snprintf_buf, "got back 0x%x", rval); + Serial1.println(snprintf_buf); + } + } + + return true; +} + +bool random_trips(void) { + for (int n = 0; n < N; n++) { + __io uint16 *const start = starts[n]; + + for (int i = 0; i < 1000; i++) { + uint32 offset = rand(MEM_SIZE); + uint32 wval = rand(0xFFFF); + + *(start + offset) = wval; + uint32 rval = *(start + offset); + + if (rval != wval) { + ERR("wrote 0x%x to 0x%x, read 0x%x", wval, offset, rval); + return false; + } + } + } + return true; +} + +bool sequential_trips(void) { + static const uint32 seq_length = 300; + + for (int n = 0; n < N; n++) { + __io uint16 *const start = starts[n]; + + for (int i = 0; i < 100; i++) { + uint32 start_offset = rand(MEM_SIZE - seq_length); + + for (uint32 w = 0; w < seq_length; w++) { + uint32 offset = start_offset + w; + + *(start + offset) = w; + uint32 r = *(start + offset); + + if (w != r) { + ERR("wrote 0x%x to 0x%x, read 0x%x", w, offset, r); + return false; + } + } + } + } + return true; +} + +// ---------------------------------------------------------------------------- + +__attribute__((constructor)) void premain() { + init(); +} + +int main(void) { + setup(); + while (true) { + loop(); + } + return 0; +} + diff --git a/examples/test-fsmc.cpp b/examples/test-fsmc.cpp index 4211e4d..7db3bb7 100644 --- a/examples/test-fsmc.cpp +++ b/examples/test-fsmc.cpp @@ -1,113 +1,125 @@ +#include // for ptrdiff_t + #include "wirish.h" #include "fsmc.h" -#define LED_PIN BOARD_LED_PIN - -// System control block registers -#define SCB_BASE (SCB_Reg*)(0xE000ED00) - -// This stuff should ultimately get moved to util.h or scb.h or w/e. -// Also in interactive test program and the HardFault IRQ handler. -typedef struct { - volatile uint32 CPUID; - volatile uint32 ICSR; - volatile uint32 VTOR; - volatile uint32 AIRCR; - volatile uint32 SCR; - volatile uint32 CCR; - volatile uint32 SHPR1; - volatile uint32 SHPR2; - volatile uint32 SHPR3; - volatile uint32 SHCRS; - volatile uint32 CFSR; - volatile uint32 HFSR; - uint32 pad1; - volatile uint32 MMAR; - volatile uint32 BFAR; -} SCB_Reg; - -SCB_Reg *scb; - -uint16 *ptr; -int count = 0; +#ifndef BOARD_maple_native +#error "Sorry, this example only works on Maple Native." +#endif + +// Start of FSMC SRAM bank 1 +static uint16 *const sram_start = (uint16*)0x60000000; +// End of Maple Native SRAM chip address space (512K 16-bit words) +static uint16 *const sram_end = (uint16*)0x60080000; + +void test_single_write(void); +void test_all_addresses(void); void setup() { - uint32 id; - scb = (SCB_Reg*)SCB_BASE; - - pinMode(LED_PIN, OUTPUT); - digitalWrite(LED_PIN,1); - - Serial1.begin(9600); - Serial1.println("Hello World!"); - - Serial1.print("Init... "); - fsmc_native_sram_init(); - Serial1.println("Done."); - - // Start of channel1 SRAM bank (through to 0x63FFFFFF, though only a chunk - // of this is valid) - ptr = (uint16*)(0x60000000); - - Serial1.print("Writing... "); - *ptr = 0x1234; - Serial1.println("Done."); - - Serial1.print("Reading... "); - id = *ptr; - Serial1.print("Done: "); // shouldn't be 0xFFFFFFFF - Serial1.println(id,BIN); - - Serial1.println("Dumping System Control Block Registers"); - Serial1.print("CPUID: "); - id = scb->CPUID; - Serial1.println(id,BIN); - Serial1.print("ICSR: "); - id = scb->ICSR; - Serial1.println(id,BIN); - Serial1.print("CFSR: "); - id = scb->CFSR; - Serial1.println(id,BIN); - Serial1.print("HFSR: "); - id = scb->HFSR; - Serial1.println(id,BIN); - Serial1.print("MMAR: "); - id = scb->MMAR; - Serial1.println(id,BIN); - Serial1.print("BFAR: "); - id = scb->BFAR; - Serial1.println(id,BIN); - - Serial1.println("Now testing all memory addresses... (will hardfault at the end)"); - delay(3000); + pinMode(BOARD_LED_PIN, OUTPUT); + digitalWrite(BOARD_LED_PIN, HIGH); + + Serial1.begin(115200); + Serial1.println("*** Beginning RAM chip test"); + + test_single_write(); + test_all_addresses(); + + Serial1.println("Tests pass, finished."); } void loop() { - toggleLED(); - delay(1); - - for(int i = 0; i<100; i++) { // modify this to speed things up - count++; - ptr++; - //delay(10); // tweak this to test SRAM resiliance over time - *ptr = (0x0000FFFF & count); - if(*ptr != (0x0000FFFF & count)) { - Serial1.println("ERROR: mismatch, halting"); - while(1) { } +} + +void test_single_write() { + uint16 *ptr = sram_start; + uint16 tmp; + + Serial1.print("Writing 0x1234... "); + *ptr = 0x1234; + Serial1.println("Done."); + + Serial1.print("Reading... "); + tmp = *ptr; + Serial1.print("Done: 0x"); + Serial1.println(tmp, HEX); + + if (tmp != 0x1234) { + Serial1.println("Mismatch; abort."); + ASSERT(0); + } +} + +void test_all_addresses() { + uint32 start, end; + uint16 count = 0; + uint16 *ptr; + + Serial1.println("Now writing all memory addresses (unrolled loop)"); + // Turn off the USB interrupt, as it interferes most with timing + // (don't turn off SysTick, or we won't get micros()). + SerialUSB.end(); + start = micros(); + for (ptr = sram_start; ptr < sram_end;) { + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + *ptr++ = count++; + } + end = micros(); + SerialUSB.begin(); + Serial1.print("Done. Elapsed time (us): "); + Serial1.println(end - start); + + Serial1.println("Validating writes."); + for (ptr = sram_start, count = 0; ptr < sram_end; ptr++, count++) { + uint16 value = *ptr; + if (value != count) { + Serial1.print("mismatch: 0x"); + Serial1.print((uint32)ptr); + Serial1.print(" = 0x"); + Serial1.print(value, HEX); + Serial1.print(", should be 0x"); + Serial1.print(count, HEX); + Serial1.println("."); + ASSERT(0); } - } + } + Serial1.println("Done; all writes seem valid."); + + ptrdiff_t nwrites = sram_end - sram_start; + double us_per_write = double(end-start) / double(nwrites); + Serial1.print("Number of writes = "); + Serial1.print(nwrites); + Serial1.print("; avg. time per write = "); + Serial1.print(us_per_write); + Serial1.print(" us ("); + Serial1.print(1 / us_per_write); + Serial1.println(" MHz)"); +} - Serial1.print((uint32)(ptr),HEX); - Serial1.print(": "); - Serial1.println(*ptr,BIN); +__attribute__((constructor)) void premain() { + init(); } int main(void) { - init(); - setup(); + setup(); + + while (true) { + loop(); + } - while (1) { - loop(); - } - return 0; + return 0; } diff --git a/libmaple/fsmc.c b/libmaple/fsmc.c index 1561add..70d7e0d 100644 --- a/libmaple/fsmc.c +++ b/libmaple/fsmc.c @@ -33,19 +33,10 @@ #ifdef STM32_HIGH_DENSITY -/* These values determined for a particular SRAM chip by following the - * calculations in the ST FSMC application note. */ -#define FSMC_ADDSET 0x0 -#define FSMC_DATAST 0x3 - -/* Sets up the FSMC peripheral to use the SRAM chip on the maple - * native as an external segment of system memory space. This - * implementation is for the IS62WV51216BLL 8mbit chip (55ns - * timing) */ -void fsmc_native_sram_init(void) { - FSMC_Bank *bank; - - /* First we setup all the GPIO pins. */ +/** + * Configure FSMC GPIOs for use with SRAM. + */ +void fsmc_sram_init_gpios(void) { /* Data lines... */ gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP); gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP); @@ -96,42 +87,6 @@ void fsmc_native_sram_init(void) { gpio_set_mode(GPIOE, 0, GPIO_AF_OUTPUT_PP); // NBL0 gpio_set_mode(GPIOE, 1, GPIO_AF_OUTPUT_PP); // NBL1 - - /* Next enable the clock */ - rcc_clk_enable(RCC_FSMC); - - /* Then we configure channel 1 the FSMC SRAM peripheral (all SRAM - * channels are in "Bank 1" of the FSMC) */ - bank = (FSMC_Bank*)(FSMC1_BASE); - - /* Everything else is cleared (BCR1) */ - bank->BCR = 0x0000; - - /* Memory type is SRAM */ - bank->BCR &= ~(FSMC_BCR_MTYP); // '00' - - /* Databus width is 16bits */ - bank->BCR &= ~(FSMC_BCR_MWID); - bank->BCR |= 0x1 << 4; // '01' - - /* Memory is nonmultiplexed */ - bank->BCR &= ~(FSMC_BCR_MUXEN); // '0' - - /* Need write enable to write to the chip */ - bank->BCR |= FSMC_BCR_WREN; - - /* Set ADDSET */ - bank->BTR &= ~(FSMC_BTR_ADDSET); - bank->BTR |= (FSMC_BTR_ADDSET | FSMC_ADDSET); - - /* Set DATAST */ - bank->BTR &= ~(FSMC_BTR_DATAST); - bank->BTR |= (FSMC_BTR_DATAST | (FSMC_DATAST << 8)); - - /* Enable channel 1 */ - bank->BCR |= FSMC_BCR_MBKEN; // '1' - - /* (FSMC_BWTR3 not used for this simple configuration.) */ } #endif /* STM32_HIGH_DENSITY */ diff --git a/libmaple/fsmc.h b/libmaple/fsmc.h index fed6894..fccaf0b 100644 --- a/libmaple/fsmc.h +++ b/libmaple/fsmc.h @@ -39,55 +39,273 @@ extern "C"{ #ifdef STM32_HIGH_DENSITY -// There are 4 FSMC chip-select devices; here are the SRAM-specific registers -// for each - -#define FSMC1_BASE 0xA0000000 -#define FSMC2_BASE 0xA0000008 -#define FSMC3_BASE 0xA0000010 -#define FSMC4_BASE 0xA0000018 - -typedef struct { - volatile uint32 BCR; - volatile uint32 BTR; - //uint32 pad[62]; // double check this? - //__io uint32 BWTR; -} FSMC_Bank; - -// And here are the register bit ranges -#define FSMC_BCR_MBKEN 0b00000000000000000000000000000001 -#define FSMC_BCR_MUXEN 0b00000000000000000000000000000010 -#define FSMC_BCR_MTYP 0b00000000000000000000000000001100 -#define FSMC_BCR_MWID 0b00000000000000000000000000110000 -#define FSMC_BCR_FACCEN 0b00000000000000000000000001000000 -#define FSMC_BCR_BURSTEN 0b00000000000000000000000100000000 -#define FSMC_BCR_WAITPOL 0b00000000000000000000001000000000 -#define FSMC_BCR_WRAPMOD 0b00000000000000000000010000000000 -#define FSMC_BCR_WAITCFG 0b00000000000000000000100000000000 -#define FSMC_BCR_WREN 0b00000000000000000001000000000000 -#define FSMC_BCR_WAITEN 0b00000000000000000010000000000000 -#define FSMC_BCR_EXTMOD 0b00000000000000000100000000000000 -#define FSMC_BCR_CBURSTRW 0b00000000000010000000000000000000 -#define FSMC_BTR_ADDSET 0b00000000000000000000000000001111 -#define FSMC_BTR_ADDHOLD 0b00000000000000000000000011110000 -#define FSMC_BTR_DATAST 0b00000000000000001111111100000000 -#define FSMC_BTR_BUSTURN 0b00000000000011110000000000000000 -#define FSMC_BTR_CLKDIV 0b00000000111100000000000000000000 -#define FSMC_BTR_DATALAT 0b00001111000000000000000000000000 -#define FSMC_BTR_ACCMOD 0b00110000000000000000000000000000 -#define FSMC_BWTR_ADDSET 0b00000000000000000000000000001111 -#define FSMC_BWTR_ADDHLD 0b00000000000000000000000011110000 -#define FSMC_BWTR_DATAST 0b00000000000000001111111100000000 -#define FSMC_BWTR_CLKDIV 0b00000000111100000000000000000000 -#define FSMC_BWTR_DATLAT 0b00001111000000000000000000000000 -#define FSMC_BWTR_ACCMOD 0b00110000000000000000000000000000 - -void fsmc_native_sram_init(void); +/* + * Register maps and devices + */ + +/** FSMC register map type */ +typedef struct fsmc_reg_map { + __io uint32 BCR1; /**< SRAM/NOR-Flash chip-select control register 1 */ + __io uint32 BTR1; /**< SRAM/NOR-Flash chip-select timing register 1 */ + __io uint32 BCR2; /**< SRAM/NOR-Flash chip-select control register 2 */ + __io uint32 BTR2; /**< SRAM/NOR-Flash chip-select timing register 2 */ + __io uint32 BCR3; /**< SRAM/NOR-Flash chip-select control register 3 */ + __io uint32 BTR3; /**< SRAM/NOR-Flash chip-select timing register 3 */ + __io uint32 BCR4; /**< SRAM/NOR-Flash chip-select control register 4 */ + __io uint32 BTR4; /**< SRAM/NOR-Flash chip-select timing register 4 */ + const uint8 RESERVED1[64]; /**< Reserved */ + __io uint32 PCR2; /**< PC Card/NAND Flash control register 2 */ + __io uint32 SR2; /**< FIFO status and interrupt register 2 */ + __io uint32 PMEM2; /**< Common memory space timing register 2 */ + __io uint32 PATT2; /**< Attribute memory space timing register 2 */ + const uint8 RESERVED2[4]; /**< Reserved */ + __io uint32 ECCR2; /**< ECC result register 2 */ + const uint8 RESERVED3[2]; + __io uint32 PCR3; /**< PC Card/NAND Flash control register 3 */ + __io uint32 SR3; /**< FIFO status and interrupt register 3 */ + __io uint32 PMEM3; /**< Common memory space timing register 3 */ + __io uint32 PATT3; /**< Attribute memory space timing register 3 */ + const uint32 RESERVED4; /**< Reserved */ + __io uint32 ECCR3; /**< ECC result register 3 */ + const uint8 RESERVED5[8]; /**< Reserved */ + __io uint32 PCR4; /**< PC Card/NAND Flash control register 4 */ + __io uint32 SR4; /**< FIFO status and interrupt register 4 */ + __io uint32 PMEM4; /**< Common memory space timing register 4 */ + __io uint32 PATT4; /**< Attribute memory space timing register 4 */ + __io uint32 PIO4; /**< I/O space timing register 4 */ + const uint8 RESERVED6[80]; /**< Reserved */ + __io uint32 BWTR1; /**< SRAM/NOR-Flash write timing register 1 */ + const uint32 RESERVED7; /**< Reserved */ + __io uint32 BWTR2; /**< SRAM/NOR-Flash write timing register 2 */ + const uint32 RESERVED8; /**< Reserved */ + __io uint32 BWTR3; /**< SRAM/NOR-Flash write timing register 3 */ + const uint32 RESERVED9; /**< Reserved */ + __io uint32 BWTR4; /**< SRAM/NOR-Flash write timing register 4 */ +} __attribute__((packed)) fsmc_reg_map; + +#define __FSMC_B 0xA0000000 + +/** FSMC register map base pointer */ +#define FSMC_BASE ((struct fsmc_reg_map*)__FSMC_B) + +/** FSMC NOR/PSRAM register map type */ +typedef struct fsmc_nor_psram_reg_map { + __io uint32 BCR; /**< Chip-select control register */ + __io uint32 BTR; /**< Chip-select timing register */ + const uint8 RESERVED[252]; /**< Reserved */ + __io uint32 BWTR; /**< Write timing register */ +} fsmc_nor_psram_reg_map; + +/** FSMC NOR/PSRAM base pointer 1 */ +#define FSMC_NOR_PSRAM1_BASE ((struct fsmc_nor_psram_reg_map*)__FSMC_B) + +/** FSMC NOR/PSRAM base pointer 2 */ +#define FSMC_NOR_PSRAM2_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B + 0x8)) + +/** FSMC NOR/PSRAM base pointer 3 */ +#define FSMC_NOR_PSRAM3_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B+0x10)) + +/** FSMC NOR/PSRAM base pointer 4 */ +#define FSMC_NOR_PSRAM4_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B+0x18)) + +/* + * Register bit definitions + */ + +/* NOR/PSRAM chip-select control registers */ + +#define FSMC_BCR_CBURSTRW_BIT 19 +#define FSMC_BCR_ASYNCWAIT_BIT 15 +#define FSMC_BCR_EXTMOD_BIT 14 +#define FSMC_BCR_WAITEN_BIT 13 +#define FSMC_BCR_WREN_BIT 12 +#define FSMC_BCR_WAITCFG_BIT 11 +#define FSMC_BCR_WRAPMOD_BIT 10 +#define FSMC_BCR_WAITPOL_BIT 9 +#define FSMC_BCR_BURSTEN_BIT 8 +#define FSMC_BCR_FACCEN_BIT 6 +#define FSMC_BCR_MUXEN_BIT 1 +#define FSMC_BCR_MBKEN_BIT 0 + +#define FSMC_BCR_CBURSTRW BIT(FSMC_BCR_CBURSTRW_BIT) +#define FSMC_BCR_ASYNCWAIT BIT(FSMC_BCR_ASYNCWAIT_BIT) +#define FSMC_BCR_EXTMOD BIT(FSMC_BCR_EXTMOD_BIT) +#define FSMC_BCR_WAITEN BIT(FSMC_BCR_WAITEN_BIT) +#define FSMC_BCR_WREN BIT(FSMC_BCR_WREN_BIT) +#define FSMC_BCR_WAITCFG BIT(FSMC_BCR_WAITCFG_BIT) +#define FSMC_BCR_WRAPMOD BIT(FSMC_BCR_WRAPMOD_BIT) +#define FSMC_BCR_WAITPOL BIT(FSMC_BCR_WAITPOL_BIT) +#define FSMC_BCR_BURSTEN BIT(FSMC_BCR_BURSTEN_BIT) +#define FSMC_BCR_FACCEN BIT(FSMC_BCR_FACCEN_BIT) +#define FSMC_BCR_MWID (0x3 << 4) +#define FSMC_BCR_MWID_8BITS (0x0 << 4) +#define FSMC_BCR_MWID_16BITS (0x1 << 4) +#define FSMC_BCR_MTYP (0x3 << 2) +#define FSMC_BCR_MTYP_SRAM (0x0 << 2) +#define FSMC_BCR_MTYP_PSRAM (0x1 << 2) +#define FSMC_BCR_MTYP_NOR_FLASH (0x2 << 2) +#define FSMC_BCR_MUXEN BIT(FSMC_BCR_MUXEN_BIT) +#define FSMC_BCR_MBKEN BIT(FSMC_BCR_MBKEN_BIT) + +/* SRAM/NOR-Flash chip-select timing registers */ + +#define FSMC_BTR_ACCMOD (0x3 << 28) +#define FSMC_BTR_ACCMOD_A (0x0 << 28) +#define FSMC_BTR_ACCMOD_B (0x1 << 28) +#define FSMC_BTR_ACCMOD_C (0x2 << 28) +#define FSMC_BTR_ACCMOD_D (0x3 << 28) +#define FSMC_BTR_DATLAT (0xF << 24) +#define FSMC_BTR_CLKDIV (0xF << 20) +#define FSMC_BTR_BUSTURN (0xF << 16) +#define FSMC_BTR_DATAST (0xFF << 8) +#define FSMC_BTR_ADDHLD (0xF << 4) +#define FSMC_BTR_ADDSET 0xF + +/* SRAM/NOR-Flash write timing registers */ + +#define FSMC_BWTR_ACCMOD (0x3 << 28) +#define FSMC_BWTR_ACCMOD_A (0x0 << 28) +#define FSMC_BWTR_ACCMOD_B (0x1 << 28) +#define FSMC_BWTR_ACCMOD_C (0x2 << 28) +#define FSMC_BWTR_ACCMOD_D (0x3 << 28) +#define FSMC_BWTR_DATLAT (0xF << 24) +#define FSMC_BWTR_CLKDIV (0xF << 20) +#define FSMC_BWTR_DATAST (0xFF << 8) +#define FSMC_BWTR_ADDHLD (0xF << 4) +#define FSMC_BWTR_ADDSET 0xF + +/* NAND Flash/PC Card controller registers */ + +#define FSMC_PCR_ECCEN_BIT 6 +#define FSMC_PCR_PTYP_BIT 3 +#define FSMC_PCR_PBKEN_BIT 2 +#define FSMC_PCR_PWAITEN_BIT 1 + +#define FSMC_PCR_ECCPS (0x7 << 17) +#define FSMC_PCR_ECCPS_256B (0x0 << 17) +#define FSMC_PCR_ECCPS_512B (0x1 << 17) +#define FSMC_PCR_ECCPS_1024B (0x2 << 17) +#define FSMC_PCR_ECCPS_2048B (0x3 << 17) +#define FSMC_PCR_ECCPS_4096B (0x4 << 17) +#define FSMC_PCR_ECCPS_8192B (0x5 << 17) +#define FSMC_PCR_TAR (0xF << 13) +#define FSMC_PCR_TCLR (0xF << 9) +#define FSMC_PCR_ECCEN BIT(FSMC_PCR_ECCEN_BIT) +#define FSMC_PCR_PWID (0x3 << 4) +#define FSMC_PCR_PWID_8BITS (0x0 << 4) +#define FSMC_PCR_PWID_16BITS (0x1 << 4) +#define FSMC_PCR_PTYP BIT(FSMC_PCR_PTYP_BIT) +#define FSMC_PCR_PTYP_PC_CF_PCMCIA (0x0 << FSMC_PCR_PTYP_BIT) +#define FSMC_PCR_PTYP_NAND (0x1 << FSMC_PCR_PTYP_BIT) +#define FSMC_PCR_PBKEN BIT(FSMC_PCR_PBKEN_BIT) +#define FSMC_PCR_PWAITEN BIT(FSMC_PCR_PWAITEN_BIT) + +/* FIFO status and interrupt registers */ + +#define FSMC_SR_FEMPT_BIT 6 +#define FSMC_SR_IFEN_BIT 5 +#define FSMC_SR_ILEN_BIT 4 +#define FSMC_SR_IREN_BIT 3 +#define FSMC_SR_IFS_BIT 2 +#define FSMC_SR_ILS_BIT 1 +#define FSMC_SR_IRS_BIT 0 + +#define FSMC_SR_FEMPT BIT(FSMC_SR_FEMPT_BIT) +#define FSMC_SR_IFEN BIT(FSMC_SR_IFEN_BIT) +#define FSMC_SR_ILEN BIT(FSMC_SR_ILEN_BIT) +#define FSMC_SR_IREN BIT(FSMC_SR_IREN_BIT) +#define FSMC_SR_IFS BIT(FSMC_SR_IFS_BIT) +#define FSMC_SR_ILS BIT(FSMC_SR_ILS_BIT) +#define FSMC_SR_IRS BIT(FSMC_SR_IRS_BIT) + +/* Common memory space timing registers */ + +#define FSMC_PMEM_MEMHIZ (0xFF << 24) +#define FSMC_PMEM_MEMHOLD (0xFF << 16) +#define FSMC_PMEM_MEMWAIT (0xFF << 8) +#define FSMC_PMEM_MEMSET 0xFF + +/* Attribute memory space timing registers */ + +#define FSMC_PATT_ATTHIZ (0xFF << 24) +#define FSMC_PATT_ATTHOLD (0xFF << 16) +#define FSMC_PATT_ATTWAIT (0xFF << 8) +#define FSMC_PATT_ATTSET 0xFF + +/* I/O space timing register 4 */ + +#define FSMC_PIO_IOHIZ (0xFF << 24) +#define FSMC_PIO_IOHOLD (0xFF << 16) +#define FSMC_PIO_IOWAIT (0xFF << 8) +#define FSMC_PIO_IOSET 0xFF + +/* + * Memory bank boundary addresses + */ + +/** Pointer to base address of FSMC memory bank 1 (split into 4 + * regions, each supporting 1 NOR Flash, SRAM, or PSRAM chip) */ +#define FSMC_BANK1 ((void*)0x60000000) + +/** Pointer to base address of FSMC memory bank 1, region 1 (for NOR/PSRAM) */ +#define FSMC_NOR_PSRAM_REGION1 FSMC_BANK1 + +/** Pointer to base address of FSMC memory bank 1, region 2 (for NOR/PSRAM) */ +#define FSMC_NOR_PSRAM_REGION2 ((void*)0x64000000) + +/** Pointer to base address of FSMC memory bank 1, region 3 (for NOR/PSRAM) */ +#define FSMC_NOR_PSRAM_REGION3 ((void*)0x68000000) + +/** Pointer to base address of FSMC memory bank 1, region 4 (for NOR/PSRAM) */ +#define FSMC_NOR_PSRAM_REGION4 ((void*)0x6C000000) + +/** Pointer to base address of FSMC memory bank 2 (for NAND Flash) */ +#define FSMC_BANK2 ((void*)0x70000000) + +/** Pointer to base address of FSMC memory bank 3 (for NAND Flash) */ +#define FSMC_BANK3 ((void*)0x80000000) + +/** Pointer to base address of FSMC memory bank 4 (for PC card devices */ +#define FSMC_BANK4 ((void*)0x90000000) + +/* + * SRAM/NOR Flash routines + */ + +void fsmc_sram_init_gpios(void); + +/** + * Set the DATAST bits in the given NOR/PSRAM register map's + * chip-select timing register (FSMC_BTR). + * + * @param regs NOR Flash/PSRAM register map whose chip-select timing + * register to set. + * @param datast Value to use for DATAST bits. + */ +static inline void fsmc_nor_psram_set_datast(fsmc_nor_psram_reg_map *regs, + uint8 datast) { + regs->BTR &= ~FSMC_BTR_DATAST; + regs->BTR |= datast << 8; +} + +/** + * Set the ADDHLD bits in the given NOR/PSRAM register map's chip + * select timing register (FSMC_BTRx). + * + * @param regs NOR Flash/PSRAM register map whose chip-select timing + * register to set. + * @param addset Value to use for ADDSET bits. + */ +static inline void fsmc_nor_psram_set_addset(fsmc_nor_psram_reg_map *regs, + uint8 addset) { + regs->BTR &= ~FSMC_BTR_ADDSET; + regs->BTR |= addset & 0xF; +} #endif /* STM32_HIGH_DENSITY */ #ifdef __cplusplus -} // extern "C" +} /* extern "C" */ #endif #endif diff --git a/wirish/native_sram.cpp b/wirish/native_sram.cpp new file mode 100644 index 0000000..5e8095f --- /dev/null +++ b/wirish/native_sram.cpp @@ -0,0 +1,45 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +#include "native_sram.h" +#include "libmaple.h" +#include "fsmc.h" +#include "rcc.h" + +#ifdef BOARD_maple_native + +void initNativeSRAM(void) { + fsmc_nor_psram_reg_map *regs = FSMC_NOR_PSRAM1_BASE; + + fsmc_sram_init_gpios(); + rcc_clk_enable(RCC_FSMC); + + regs->BCR = FSMC_BCR_WREN | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN; + fsmc_nor_psram_set_addset(regs, 0); + fsmc_nor_psram_set_datast(regs, 3); +} + +#endif diff --git a/wirish/native_sram.h b/wirish/native_sram.h new file mode 100644 index 0000000..7724667 --- /dev/null +++ b/wirish/native_sram.h @@ -0,0 +1,43 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +#ifdef BOARD_maple_native + +#ifndef _NATIVE_SRAM_H_ +#define _NATIVE_SRAM_H_ + +/** + * Sets up the FSMC peripheral to use the SRAM chip on the Maple + * Native as an external segment of system memory space. + * + * This implementation is for the IS62WV51216BLL 8Mb chip (55ns + * timing, 512K x 16 bits). + */ +void initNativeSRAM(void); + +#endif + +#endif diff --git a/wirish/rules.mk b/wirish/rules.mk index cea34f5..3dd4b2d 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -27,6 +27,7 @@ cppSRCS_$(d) := wirish_math.cpp \ pwm.cpp \ ext_interrupts.cpp \ wirish_digital.cpp \ + native_sram.cpp \ boards.cpp cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index 6d77bc8..c5a9e30 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -41,6 +41,7 @@ #include "fsmc.h" #include "dac.h" #include "flash.h" +#include "native_sram.h" void init(void) { /* make sure the flash is ready before spinning the high speed clock up */ @@ -48,7 +49,7 @@ void init(void) { flash_set_latency(FLASH_WAIT_STATE_2); #ifdef BOARD_maple_native - fsmc_native_sram_init(); + initNativeSRAM(); #endif /* initialize clocks */ -- cgit v1.2.3 From 403498a28956507bb3063e6d7c190639c0279f47 Mon Sep 17 00:00:00 2001 From: Perry Hung Date: Mon, 21 Mar 2011 02:25:23 -0400 Subject: Revert "RCC refactor, bugfixes" This reverts commit e4807a5010f59ab863ad2c96dc14caf65bf1ae60. --- libmaple/adc.c | 4 +- libmaple/adc.h | 6 +- libmaple/bkp.c | 4 +- libmaple/dac.c | 4 - libmaple/dac.h | 4 - libmaple/exti.c | 18 +- libmaple/gpio.c | 2 +- libmaple/rcc.c | 200 ++++++++------------ libmaple/rcc.h | 541 +++++++++++------------------------------------------- wirish/boards.cpp | 2 +- wirish/wirish.cpp | 2 +- 11 files changed, 212 insertions(+), 575 deletions(-) (limited to 'wirish') diff --git a/libmaple/adc.c b/libmaple/adc.c index 3d38596..9626a40 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -126,8 +126,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { * @param dev adc device */ static void adc_calibrate(const adc_dev *dev) { - __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3); - __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2); + __io uint32 *rstcal_bit = bb_peripv(&(dev->regs->CR2), 3); + __io uint32 *cal_bit = bb_peripv(&(dev->regs->CR2), 2); *rstcal_bit = 1; while (*rstcal_bit) diff --git a/libmaple/adc.h b/libmaple/adc.h index 53ef032..4811dbc 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -175,7 +175,7 @@ static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { * @param enable If 1, conversion on external events is enabled, 0 to disable */ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { - *bb_perip(&dev->regs->CR2, 20) = !!enable; + *bb_peripv(&dev->regs->CR2, 20) = !!enable; } /** @@ -183,7 +183,7 @@ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { * @param dev ADC device to enable */ static inline void adc_enable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 1; + *bb_peripv(&dev->regs->CR2, 0) = 1; } /** @@ -191,7 +191,7 @@ static inline void adc_enable(const adc_dev *dev) { * @param dev ADC device to disable */ static inline void adc_disable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 0; + *bb_peripv(&dev->regs->CR2, 0) = 0; } /** diff --git a/libmaple/bkp.c b/libmaple/bkp.c index aaccb1f..b152069 100644 --- a/libmaple/bkp.c +++ b/libmaple/bkp.c @@ -57,14 +57,14 @@ void bkp_init(void) { * @see bkp_init() */ void bkp_enable_writes(void) { - *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 1; + *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 1; } /** * Disable write access to the backup registers. */ void bkp_disable_writes(void) { - *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 0; + *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 0; } /** diff --git a/libmaple/dac.c b/libmaple/dac.c index f0bdbcd..ef3a9f9 100644 --- a/libmaple/dac.c +++ b/libmaple/dac.c @@ -26,8 +26,6 @@ #include "gpio.h" #include "dac.h" -#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) - /** * @brief DAC peripheral routines. */ @@ -110,5 +108,3 @@ void dac_disable_channel(uint8 channel) { break; } } - -#endif diff --git a/libmaple/dac.h b/libmaple/dac.h index ee8a4e7..c897bb2 100644 --- a/libmaple/dac.h +++ b/libmaple/dac.h @@ -32,8 +32,6 @@ #ifndef _DAC_H_ #define _DAC_H_ -#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) - #include "rcc.h" #ifdef __cplusplus @@ -151,6 +149,4 @@ void dac_disable_channel(uint8 channel); } // extern "C" #endif -#endif /* STM32_HIGH_DENSITY, STM32_XL_DENSITY */ - #endif diff --git a/libmaple/exti.c b/libmaple/exti.c index 7f56712..8177e1e 100644 --- a/libmaple/exti.c +++ b/libmaple/exti.c @@ -98,14 +98,14 @@ void exti_attach_interrupt(afio_exti_num num, /* Set trigger mode */ switch (mode) { case EXTI_RISING: - *bb_perip(&EXTI_BASE->RTSR, num) = 1; + *bb_peripv(&EXTI_BASE->RTSR, num) = 1; break; case EXTI_FALLING: - *bb_perip(&EXTI_BASE->FTSR, num) = 1; + *bb_peripv(&EXTI_BASE->FTSR, num) = 1; break; case EXTI_RISING_FALLING: - *bb_perip(&EXTI_BASE->RTSR, num) = 1; - *bb_perip(&EXTI_BASE->FTSR, num) = 1; + *bb_peripv(&EXTI_BASE->RTSR, num) = 1; + *bb_peripv(&EXTI_BASE->FTSR, num) = 1; break; } @@ -113,7 +113,7 @@ void exti_attach_interrupt(afio_exti_num num, afio_exti_select(num, port); /* Unmask external interrupt request */ - *bb_perip(&EXTI_BASE->IMR, num) = 1; + *bb_peripv(&EXTI_BASE->IMR, num) = 1; /* Enable the interrupt line */ enable_irq(num); @@ -126,11 +126,11 @@ void exti_attach_interrupt(afio_exti_num num, */ void exti_detach_interrupt(afio_exti_num num) { /* First, mask the interrupt request */ - *bb_perip(&EXTI_BASE->IMR, num) = 0; + *bb_peripv(&EXTI_BASE->IMR, num) = 0; /* Then, clear the trigger selection registers */ - *bb_perip(&EXTI_BASE->FTSR, num) = 0; - *bb_perip(&EXTI_BASE->RTSR, num) = 0; + *bb_peripv(&EXTI_BASE->FTSR, num) = 0; + *bb_peripv(&EXTI_BASE->RTSR, num) = 0; /* Next, disable the IRQ, unless it's multiplexed and there are * other active external interrupts on the same IRQ line */ @@ -210,7 +210,7 @@ void __irq_exti15_10(void) { */ static inline void clear_pending(uint32 exti_num) { - *bb_perip(&EXTI_BASE->PR, exti_num) = 1; + *bb_peripv(&EXTI_BASE->PR, exti_num) = 1; /* If the pending bit is cleared as the last instruction in an ISR, * it won't actually be cleared in time and the ISR will fire again. * Insert a 2-cycle buffer to allow it to take effect. */ diff --git a/libmaple/gpio.c b/libmaple/gpio.c index 90be033..b08be12 100644 --- a/libmaple/gpio.c +++ b/libmaple/gpio.c @@ -61,7 +61,7 @@ static gpio_dev gpiod = { /** GPIO port D device. */ gpio_dev *GPIOD = &gpiod; -#ifdef STM32_HIGH_DENSITY +#ifdef STM32_HIGH_ static gpio_dev gpioe = { .regs = GPIOE_BASE, .clk_id = RCC_GPIOE diff --git a/libmaple/rcc.c b/libmaple/rcc.c index e49382c..2841af3 100644 --- a/libmaple/rcc.c +++ b/libmaple/rcc.c @@ -23,115 +23,97 @@ *****************************************************************************/ /** - * @file rcc.c - * @brief Clock setup, peripheral enable and reset routines. + * @brief Implements pretty much only the basic clock setup on the + * stm32, clock enable/disable and peripheral reset commands. */ #include "libmaple.h" #include "flash.h" #include "rcc.h" -#include "bitband.h" -typedef enum clock_domain { +enum { APB1, APB2, AHB -} clock_domain; +}; struct rcc_dev_info { - const clock_domain clk_domain; + const uint8 clk_domain; const uint8 line_num; }; /* device descriptor tables */ -static const __attr_flash struct rcc_dev_info rcc_dev_table[] = { - [RCC_SRAM] = { .clk_domain = AHB, .line_num = 2 }, - [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 }, - [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 }, - [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 }, - [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 }, - [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 }, - [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 }, - [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 }, - [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 }, - [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 }, - [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 }, - [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 }, - [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 }, - [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 }, - [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 }, - [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 }, - [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 }, - [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 }, - [RCC_PWR] = { .clk_domain = APB1, .line_num = 28 }, - [RCC_BKP] = { .clk_domain = APB1, .line_num = 27 }, - [RCC_CAN] = { .clk_domain = APB1, .line_num = 25 }, - [RCC_USB] = { .clk_domain = APB1, .line_num = 23 }, - [RCC_I2C1] = { .clk_domain = APB1, .line_num = 22 }, - [RCC_I2C2] = { .clk_domain = APB1, .line_num = 21 }, - [RCC_CRC] = { .clk_domain = AHB, .line_num = 6 }, - [RCC_WWDG] = { .clk_domain = APB2, .line_num = 11 }, - [RCC_FLITF] = { .clk_domain = AHB, .line_num = 4 }, -#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) - [RCC_SDIO] = { .clk_domain = AHB, .line_num = 10 }, - [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 }, - [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 }, - [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 }, - [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 }, - [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 }, - [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, - [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, - [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, - [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, - [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, - [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 }, - [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, - [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, - [RCC_SPI3] = { .clk_domain = APB1, .line_num = 15 }, -#endif -#ifdef STM32_XL_DENSITY - [RCC_TIMER9] = { .clk_domain = APB2, .line_num = 19 }, - [RCC_TIMER10] = { .clk_domain = APB2, .line_num = 20 }, - [RCC_TIMER11] = { .clk_domain = APB2, .line_num = 21 }, - [RCC_TIMER12] = { .clk_domain = APB1, .line_num = 6 }, - [RCC_TIMER13] = { .clk_domain = APB1, .line_num = 7 }, - [RCC_TIMER14] = { .clk_domain = APB1, .line_num = 8 }, -#endif +static const struct rcc_dev_info rcc_dev_table[] = { + [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 }, + [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 }, + [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 }, + [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 }, + [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 }, // High-density only + [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 }, // High-density only + [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 }, // High-density only + [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 }, + [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 }, + [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 }, + [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 }, + [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 }, + [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 }, + [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 }, + [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, // High-density only + [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, // High-density only + [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 }, + [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 }, + [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 }, + [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 }, + [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, // High-density only + [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, // High-density only + [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, // High-density only + [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 }, // High-density only + [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 }, + [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 }, + [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 }, // High-density only + [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, // High-density only + [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 }, + [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, // High-density only + [RCC_PWR] = { .clk_domain = APB1, .line_num = 28}, + [RCC_BKP] = { .clk_domain = APB1, .line_num = 27} }; /** * @brief Initialize the clock control system. Initializes the system * clock source to use the PLL driven by an external oscillator * @param sysclk_src system clock source, must be PLL - * @param pll_src pll clock source, must be RCC_CFGR_PLLSRC_HSE + * @param pll_src pll clock source, must be HSE * @param pll_mul pll multiplier */ void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) { - uint32 cfgr; - /* Assume that we're going to clock the chip off the PLL, fed by * the HSE */ ASSERT(sysclk_src == RCC_CLKSRC_PLL && - pll_src == RCC_CFGR_PLLSRC_HSE); + pll_src == RCC_PLLSRC_HSE); + + uint32 cfgr = 0; + uint32 cr = RCC_READ_CR(); - RCC_BASE->CFGR = pll_src | pll_mul; + cfgr = (pll_src | pll_mul); + RCC_WRITE_CFGR(cfgr); - /* Turn on the HSE */ - *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1; - while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_HSERDY_BIT))) + /* Turn on the HSE */ + cr |= RCC_CR_HSEON; + RCC_WRITE_CR(cr); + while (!(RCC_READ_CR() & RCC_CR_HSERDY)) ; - /* Now the PLL */ - *bb_perip(&RCC_BASE->CR, RCC_CR_PLLON_BIT) = 1; - while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_PLLRDY_BIT))) + /* Now the PLL */ + cr |= RCC_CR_PLLON; + RCC_WRITE_CR(cr); + while (!(RCC_READ_CR() & RCC_CR_PLLRDY)) ; /* Finally, let's switch over to the PLL */ - cfgr = RCC_BASE->CFGR; cfgr &= ~RCC_CFGR_SW; cfgr |= RCC_CFGR_SW_PLL; - RCC_BASE->CFGR = cfgr; - while ((RCC_BASE->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL) + RCC_WRITE_CFGR(cfgr); + while ((RCC_READ_CFGR() & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL) ; } @@ -139,23 +121,16 @@ void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) { * @brief Turn on the clock line on a device * @param device Clock ID of the device to turn on. */ -void rcc_clk_enable(rcc_clk_id id) { - uint8 lnum = rcc_dev_table[id].line_num; - __io uint32 *enr; - - switch(rcc_dev_table[id].clk_domain) { - case APB1: - enr = &RCC_BASE->APB1ENR; - break; - case APB2: - enr = &RCC_BASE->APB2ENR; - break; - case AHB: - enr = &RCC_BASE->AHBENR; - break; - } - - *bb_perip(enr, lnum) = 1; +void rcc_clk_enable(rcc_clk_id device) { + static const uint32 enable_regs[] = { + [APB1] = RCC_APB1ENR, + [APB2] = RCC_APB2ENR, + [AHB] = RCC_AHBENR, + }; + + uint8 clk_domain = rcc_dev_table[device].clk_domain; + + __set_bits(enable_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); } /** @@ -163,7 +138,7 @@ void rcc_clk_enable(rcc_clk_id id) { * @param prescaler prescaler to set * @param divider prescaler divider */ -void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) { +void rcc_set_prescaler(uint32 prescaler, uint32 divider) { static const uint32 masks[] = { [RCC_PRESCALER_AHB] = RCC_CFGR_HPRE, [RCC_PRESCALER_APB1] = RCC_CFGR_PPRE1, @@ -171,39 +146,26 @@ void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) { [RCC_PRESCALER_USB] = RCC_CFGR_USBPRE, [RCC_PRESCALER_ADC] = RCC_CFGR_ADCPRE, }; - uint32 cfgr; - cfgr = RCC_BASE->CFGR; + uint32 cfgr = RCC_READ_CFGR(); + cfgr &= ~masks[prescaler]; cfgr |= divider; - RCC_BASE->CFGR = cfgr; + RCC_WRITE_CFGR(cfgr); } /** - * @brief Reset a device - * @param device Clock ID of the device to reset; the device must be - * on APB1 or APB2. + * @brief reset a device + * @param device Clock ID of the device to reset. */ -void rcc_reset_dev(rcc_clk_id id) { - uint8 lnum = rcc_dev_table[id].line_num; - __io uint32 *rstr = 0; - - switch (rcc_dev_table[id].clk_domain) { - case APB1: - rstr = &RCC_BASE->APB1RSTR; - break; - case APB2: - rstr = &RCC_BASE->APB2RSTR; - break; - case AHB: - ASSERT(0); - break; - } - - if (rstr == 0) { - return; - } - - *bb_perip(rstr, lnum) = 1; - *bb_perip(rstr, lnum) = 0; +void rcc_reset_dev(rcc_clk_id device) { + static const uint32 reset_regs[] = { + [APB1] = RCC_APB1RSTR, + [APB2] = RCC_APB2RSTR, + }; + + uint8 clk_domain = rcc_dev_table[device].clk_domain; + + __set_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); + __clear_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num)); } diff --git a/libmaple/rcc.h b/libmaple/rcc.h index 83b34ed..8697e01 100644 --- a/libmaple/rcc.h +++ b/libmaple/rcc.h @@ -24,7 +24,7 @@ /** * @file rcc.h - * @brief Reset and clock control (RCC) definitions and prototypes + * @brief reset and clock control definitions and prototypes */ #include "libmaple_types.h" @@ -36,451 +36,78 @@ extern "C"{ #endif -/** RCC register map type */ -typedef struct rcc_reg_map { - __io uint32 CR; /**< Clock control register */ - __io uint32 CFGR; /**< Clock configuration register */ - __io uint32 CIR; /**< Clock interrupt register */ - __io uint32 APB2RSTR; /**< APB2 peripheral reset register */ - __io uint32 APB1RSTR; /**< APB1 peripheral reset register */ - __io uint32 AHBENR; /**< AHB peripheral clock enable register */ - __io uint32 APB2ENR; /**< APB2 peripheral clock enable register */ - __io uint32 APB1ENR; /**< APB1 peripheral clock enable register */ - __io uint32 BDCR; /**< Backup domain control register */ - __io uint32 CSR; /**< Control/status register */ -} rcc_reg_map; - -/* - * RCC register map base address - */ - -#define RCC_BASE ((rcc_reg_map*)0x40021000) - -/* - * RCC register bit definitions - */ - -/* Clock control register */ - -#define RCC_CR_PLLRDY_BIT 25 -#define RCC_CR_PLLON_BIT 24 -#define RCC_CR_CSSON_BIT 19 -#define RCC_CR_HSEBYP_BIT 18 -#define RCC_CR_HSERDY_BIT 17 -#define RCC_CR_HSEON_BIT 16 -#define RCC_CR_HSIRDY_BIT 1 -#define RCC_CR_HSION_BIT 0 - -#define RCC_CR_PLLRDY BIT(RCC_CR_PLLRDY_BIT) -#define RCC_CR_PLLON BIT(RCC_CR_PLLON_BIT) -#define RCC_CR_CSSON BIT(RCC_CR_CSSON_BIT) -#define RCC_CR_HSEBYP BIT(RCC_CR_HSEBYP_BIT) -#define RCC_CR_HSERDY BIT(RCC_CR_HSERDY_BIT) -#define RCC_CR_HSEON BIT(RCC_CR_HSEON_BIT) -#define RCC_CR_HSICAL (0xFF << 8) -#define RCC_CR_HSITRIM (0x1F << 3) -#define RCC_CR_HSIRDY BIT(RCC_CR_HSIRDY_BIT) -#define RCC_CR_HSION BIT(RCC_CR_HSION_BIT) - -/* Clock configuration register */ - -#define RCC_CFGR_USBPRE_BIT 22 -#define RCC_CFGR_PLLXTPRE_BIT 17 -#define RCC_CFGR_PLLSRC_BIT 16 - -#define RCC_CFGR_MCO (0x7 << 24) -#define RCC_CFGR_USBPRE BIT(RCC_CFGR_USBPRE_BIT) -#define RCC_CFGR_PLLMUL (0xF << 18) -#define RCC_CFGR_PLLMUL_2 (0x0 << 18) -#define RCC_CFGR_PLLMUL_3 (0x1 << 18) -#define RCC_CFGR_PLLMUL_4 (0x2 << 18) -#define RCC_CFGR_PLLMUL_5 (0x3 << 18) -#define RCC_CFGR_PLLMUL_6 (0x4 << 18) -#define RCC_CFGR_PLLMUL_7 (0x5 << 18) -#define RCC_CFGR_PLLMUL_8 (0x6 << 18) -#define RCC_CFGR_PLLMUL_9 (0x7 << 18) -#define RCC_CFGR_PLLMUL_10 (0x8 << 18) -#define RCC_CFGR_PLLMUL_11 (0x9 << 18) -#define RCC_CFGR_PLLMUL_12 (0xA << 18) -#define RCC_CFGR_PLLMUL_13 (0xB << 18) -#define RCC_CFGR_PLLMUL_14 (0xC << 18) -#define RCC_CFGR_PLLMUL_15 (0xD << 18) -#define RCC_CFGR_PLLMUL_16 (0xE << 18) -#define RCC_CFGR_PLLXTPRE BIT(RCC_CFGR_PLLXTPRE_BIT) -#define RCC_CFGR_PLLSRC BIT(RCC_CFGR_PLLSRC_BIT) -#define RCC_CFGR_PLLSRC_HSI_DIV_2 (0 << RCC_CFGR_PLLSRC_BIT) -#define RCC_CFGR_PLLSRC_HSE (1 << RCC_CFGR_PLLSRC_BIT) -#define RCC_CFGR_ADCPRE (0x3 << 14) -#define RCC_CFGR_PPRE2 (0x7 << 11) -#define RCC_CFGR_PPRE1 (0x7 << 8) -#define RCC_CFGR_HPRE (0xF << 4) -#define RCC_CFGR_SWS (0x3 << 2) -#define RCC_CFGR_SWS_PLL (0x2 << 2) -#define RCC_CFGR_SWS_HSE (0x1 << 2) -#define RCC_CFGR_SW (0x3 << 0) -#define RCC_CFGR_SW_PLL (0x2 << 0) -#define RCC_CFGR_SW_HSE (0x1 << 0) - -/* Clock interrupt register */ - -#define RCC_CIR_CSSC_BIT 23 -#define RCC_CIR_PLLRDYC_BIT 20 -#define RCC_CIR_HSERDYC_BIT 19 -#define RCC_CIR_HSIRDYC_BIT 18 -#define RCC_CIR_LSERDYC_BIT 17 -#define RCC_CIR_LSIRDYC_BIT 16 -#define RCC_CIR_PLLRDYIE_BIT 12 -#define RCC_CIR_HSERDYIE_BIT 11 -#define RCC_CIR_HSIRDYIE_BIT 10 -#define RCC_CIR_LSERDYIE_BIT 9 -#define RCC_CIR_LSIRDYIE_BIT 8 -#define RCC_CIR_CSSF_BIT 7 -#define RCC_CIR_PLLRDYF_BIT 4 -#define RCC_CIR_HSERDYF_BIT 3 -#define RCC_CIR_HSIRDYF_BIT 2 -#define RCC_CIR_LSERDYF_BIT 1 -#define RCC_CIR_LSIRDYF_BIT 0 - -#define RCC_CIR_CSSC BIT(RCC_CIR_CSSC_BIT) -#define RCC_CIR_PLLRDYC BIT(RCC_CIR_PLLRDYC_BIT) -#define RCC_CIR_HSERDYC BIT(RCC_CIR_HSERDYC_BIT) -#define RCC_CIR_HSIRDYC BIT(RCC_CIR_HSIRDYC_BIT) -#define RCC_CIR_LSERDYC BIT(RCC_CIR_LSERDYC_BIT) -#define RCC_CIR_LSIRDYC BIT(RCC_CIR_LSIRDYC_BIT) -#define RCC_CIR_PLLRDYIE BIT(RCC_CIR_PLLRDYIE_BIT) -#define RCC_CIR_HSERDYIE BIT(RCC_CIR_HSERDYIE_BIT) -#define RCC_CIR_HSIRDYIE BIT(RCC_CIR_HSIRDYIE_BIT) -#define RCC_CIR_LSERDYIE BIT(RCC_CIR_LSERDYIE_BIT) -#define RCC_CIR_LSIRDYIE BIT(RCC_CIR_LSIRDYIE_BIT) -#define RCC_CIR_CSSF BIT(RCC_CIR_CSSF_BIT) -#define RCC_CIR_PLLRDYF BIT(RCC_CIR_PLLRDYF_BIT) -#define RCC_CIR_HSERDYF BIT(RCC_CIR_HSERDYF_BIT) -#define RCC_CIR_HSIRDYF BIT(RCC_CIR_HSIRDYF_BIT) -#define RCC_CIR_LSERDYF BIT(RCC_CIR_LSERDYF_BIT) -#define RCC_CIR_LSIRDYF BIT(RCC_CIR_LSIRDYF_BIT) - -/* APB2 peripheral reset register */ - -#define RCC_APB2RSTR_TIM11RST_BIT 21 -#define RCC_APB2RSTR_TIM10RST_BIT 20 -#define RCC_APB2RSTR_TIM9RST_BIT 19 -#define RCC_APB2RSTR_ADC3RST_BIT 15 -#define RCC_APB2RSTR_USART1RST_BIT 14 -#define RCC_APB2RSTR_TIM8RST_BIT 13 -#define RCC_APB2RSTR_SPI1RST_BIT 12 -#define RCC_APB2RSTR_TIM1RST_BIT 11 -#define RCC_APB2RSTR_ADC2RST_BIT 10 -#define RCC_APB2RSTR_ADC1RST_BIT 9 -#define RCC_APB2RSTR_IOPGRST_BIT 8 -#define RCC_APB2RSTR_IOPFRST_BIT 7 -#define RCC_APB2RSTR_IOPERST_BIT 6 -#define RCC_APB2RSTR_IOPDRST_BIT 5 -#define RCC_APB2RSTR_IOPCRST_BIT 4 -#define RCC_APB2RSTR_IOPBRST_BIT 3 -#define RCC_APB2RSTR_IOPARST_BIT 2 -#define RCC_APB2RSTR_AFIORST_BIT 0 - -#define RCC_APB2RSTR_TIM11RST BIT(RCC_APB2RSTR_TIM11RST_BIT) -#define RCC_APB2RSTR_TIM10RST BIT(RCC_APB2RSTR_TIM10RST_BIT) -#define RCC_APB2RSTR_TIM9RST BIT(RCC_APB2RSTR_TIM9RST_BIT) -#define RCC_APB2RSTR_ADC3RST BIT(RCC_APB2RSTR_ADC3RST_BIT) -#define RCC_APB2RSTR_USART1RST BIT(RCC_APB2RSTR_USART1RST_BIT) -#define RCC_APB2RSTR_TIM8RST BIT(RCC_APB2RSTR_TIM8RST_BIT) -#define RCC_APB2RSTR_SPI1RST BIT(RCC_APB2RSTR_SPI1RST_BIT) -#define RCC_APB2RSTR_TIM1RST BIT(RCC_APB2RSTR_TIM1RST_BIT) -#define RCC_APB2RSTR_ADC2RST BIT(RCC_APB2RSTR_ADC2RST_BIT) -#define RCC_APB2RSTR_ADC1RST BIT(RCC_APB2RSTR_ADC1RST_BIT) -#define RCC_APB2RSTR_IOPGRST BIT(RCC_APB2RSTR_IOPGRST_BIT) -#define RCC_APB2RSTR_IOPFRST BIT(RCC_APB2RSTR_IOPFRST_BIT) -#define RCC_APB2RSTR_IOPERST BIT(RCC_APB2RSTR_IOPERST_BIT) -#define RCC_APB2RSTR_IOPDRST BIT(RCC_APB2RSTR_IOPDRST_BIT) -#define RCC_APB2RSTR_IOPCRST BIT(RCC_APB2RSTR_IOPCRST_BIT) -#define RCC_APB2RSTR_IOPBRST BIT(RCC_APB2RSTR_IOPBRST_BIT) -#define RCC_APB2RSTR_IOPARST BIT(RCC_APB2RSTR_IOPARST_BIT) -#define RCC_APB2RSTR_AFIORST BIT(RCC_APB2RSTR_AFIORST_BIT) - -/* APB1 peripheral reset register */ - -#define RCC_APB1RSTR_DACRST_BIT 29 -#define RCC_APB1RSTR_PWRRST_BIT 28 -#define RCC_APB1RSTR_BKPRST_BIT 27 -#define RCC_APB1RSTR_CANRST_BIT 25 -#define RCC_APB1RSTR_USBRST_BIT 23 -#define RCC_APB1RSTR_I2C2RST_BIT 22 -#define RCC_APB1RSTR_I2C1RST_BIT 21 -#define RCC_APB1RSTR_UART5RST_BIT 20 -#define RCC_APB1RSTR_UART4RST_BIT 19 -#define RCC_APB1RSTR_UART3RST_BIT 18 -#define RCC_APB1RSTR_UART2RST_BIT 17 -#define RCC_APB1RSTR_SPI3RST_BIT 15 -#define RCC_APB1RSTR_SPI2RST_BIT 14 -#define RCC_APB1RSTR_WWDGRST_BIT 11 -#define RCC_APB1RSTR_TIM14RST_BIT 8 -#define RCC_APB1RSTR_TIM13RST_BIT 7 -#define RCC_APB1RSTR_TIM12RST_BIT 6 -#define RCC_APB1RSTR_TIM7RST_BIT 5 -#define RCC_APB1RSTR_TIM6RST_BIT 4 -#define RCC_APB1RSTR_TIM5RST_BIT 3 -#define RCC_APB1RSTR_TIM4RST_BIT 2 -#define RCC_APB1RSTR_TIM3RST_BIT 1 -#define RCC_APB1RSTR_TIM2RST_BIT 0 - -#define RCC_APB1RSTR_DACRST BIT(RCC_APB1RSTR_DACRST_BIT) -#define RCC_APB1RSTR_PWRRST BIT(RCC_APB1RSTR_PWRRST_BIT) -#define RCC_APB1RSTR_BKPRST BIT(RCC_APB1RSTR_BKPRST_BIT) -#define RCC_APB1RSTR_CANRST BIT(RCC_APB1RSTR_CANRST_BIT) -#define RCC_APB1RSTR_USBRST BIT(RCC_APB1RSTR_USBRST_BIT) -#define RCC_APB1RSTR_I2C2RST BIT(RCC_APB1RSTR_I2C2RST_BIT) -#define RCC_APB1RSTR_I2C1RST BIT(RCC_APB1RSTR_I2C1RST_BIT) -#define RCC_APB1RSTR_UART5RST BIT(RCC_APB1RSTR_UART5RST_BIT) -#define RCC_APB1RSTR_UART4RST BIT(RCC_APB1RSTR_UART4RST_BIT) -#define RCC_APB1RSTR_UART3RST BIT(RCC_APB1RSTR_UART3RST_BIT) -#define RCC_APB1RSTR_UART2RST BIT(RCC_APB1RSTR_UART2RST_BIT) -#define RCC_APB1RSTR_SPI3RST BIT(RCC_APB1RSTR_SPI3RST_BIT) -#define RCC_APB1RSTR_SPI2RST BIT(RCC_APB1RSTR_SPI2RST_BIT) -#define RCC_APB1RSTR_WWDGRST BIT(RCC_APB1RSTR_WWDGRST_BIT) -#define RCC_APB1RSTR_TIM14RST BIT(RCC_APB1RSTR_TIM14RST_BIT) -#define RCC_APB1RSTR_TIM13RST BIT(RCC_APB1RSTR_TIM13RST_BIT) -#define RCC_APB1RSTR_TIM12RST BIT(RCC_APB1RSTR_TIM12RST_BIT) -#define RCC_APB1RSTR_TIM7RST BIT(RCC_APB1RSTR_TIM7RST_BIT) -#define RCC_APB1RSTR_TIM6RST BIT(RCC_APB1RSTR_TIM6RST_BIT) -#define RCC_APB1RSTR_TIM5RST BIT(RCC_APB1RSTR_TIM5RST_BIT) -#define RCC_APB1RSTR_TIM4RST BIT(RCC_APB1RSTR_TIM4RST_BIT) -#define RCC_APB1RSTR_TIM3RST BIT(RCC_APB1RSTR_TIM3RST_BIT) -#define RCC_APB1RSTR_TIM2RST BIT(RCC_APB1RSTR_TIM2RST_BIT) - -/* AHB peripheral clock enable register */ - -#define RCC_AHBENR_SDIOEN_BIT 10 -#define RCC_AHBENR_FSMCEN_BIT 8 -#define RCC_AHBENR_CRCEN_BIT 6 -#define RCC_AHBENR_FLITFEN_BIT 4 -#define RCC_AHBENR_SRAMEN_BIT 2 -#define RCC_AHBENR_DMA2EN_BIT 1 -#define RCC_AHBENR_DMA1EN_BIT 0 - -#define RCC_AHBENR_SDIOEN BIT(RCC_AHBENR_SDIOEN_BIT) -#define RCC_AHBENR_FSMCEN BIT(RCC_AHBENR_FSMCEN_BIT) -#define RCC_AHBENR_CRCEN BIT(RCC_AHBENR_CRCEN_BIT) -#define RCC_AHBENR_FLITFEN BIT(RCC_AHBENR_FLITFEN_BIT) -#define RCC_AHBENR_SRAMEN BIT(RCC_AHBENR_SRAMEN_BIT) -#define RCC_AHBENR_DMA2EN BIT(RCC_AHBENR_DMA2EN_BIT) -#define RCC_AHBENR_DMA1EN BIT(RCC_AHBENR_DMA1EN_BIT) - -/* APB2 peripheral clock enable register */ - -#define RCC_APB2ENR_TIM11EN_BIT 21 -#define RCC_APB2ENR_TIM10EN_BIT 20 -#define RCC_APB2ENR_TIM9EN_BIT 19 -#define RCC_APB2ENR_ADC3EN_BIT 15 -#define RCC_APB2ENR_USART1EN_BIT 14 -#define RCC_APB2ENR_TIM8EN_BIT 13 -#define RCC_APB2ENR_SPI1EN_BIT 12 -#define RCC_APB2ENR_TIM1EN_BIT 11 -#define RCC_APB2ENR_ADC2EN_BIT 10 -#define RCC_APB2ENR_ADC1EN_BIT 9 -#define RCC_APB2ENR_IOPGEN_BIT 8 -#define RCC_APB2ENR_IOPFEN_BIT 7 -#define RCC_APB2ENR_IOPEEN_BIT 6 -#define RCC_APB2ENR_IOPDEN_BIT 5 -#define RCC_APB2ENR_IOPCEN_BIT 4 -#define RCC_APB2ENR_IOPBEN_BIT 3 -#define RCC_APB2ENR_IOPAEN_BIT 2 -#define RCC_APB2ENR_AFIOEN_BIT 0 - -#define RCC_APB2ENR_TIM11EN BIT(RCC_APB2ENR_TIM11EN_BIT) -#define RCC_APB2ENR_TIM10EN BIT(RCC_APB2ENR_TIM10EN_BIT) -#define RCC_APB2ENR_TIM9EN BIT(RCC_APB2ENR_TIM9EN_BIT) -#define RCC_APB2ENR_ADC3EN BIT(RCC_APB2ENR_ADC3EN_BIT) -#define RCC_APB2ENR_USART1EN BIT(RCC_APB2ENR_USART1EN_BIT) -#define RCC_APB2ENR_TIM8EN BIT(RCC_APB2ENR_TIM8EN_BIT) -#define RCC_APB2ENR_SPI1EN BIT(RCC_APB2ENR_SPI1EN_BIT) -#define RCC_APB2ENR_TIM1EN BIT(RCC_APB2ENR_TIM1EN_BIT) -#define RCC_APB2ENR_ADC2EN BIT(RCC_APB2ENR_ADC2EN_BIT) -#define RCC_APB2ENR_ADC1EN BIT(RCC_APB2ENR_ADC1EN_BIT) -#define RCC_APB2ENR_IOPGEN BIT(RCC_APB2ENR_IOPGEN_BIT) -#define RCC_APB2ENR_IOPFEN BIT(RCC_APB2ENR_IOPFEN_BIT) -#define RCC_APB2ENR_IOPEEN BIT(RCC_APB2ENR_IOPEEN_BIT) -#define RCC_APB2ENR_IOPDEN BIT(RCC_APB2ENR_IOPDEN_BIT) -#define RCC_APB2ENR_IOPCEN BIT(RCC_APB2ENR_IOPCEN_BIT) -#define RCC_APB2ENR_IOPBEN BIT(RCC_APB2ENR_IOPBEN_BIT) -#define RCC_APB2ENR_IOPAEN BIT(RCC_APB2ENR_IOPAEN_BIT) -#define RCC_APB2ENR_AFIOEN BIT(RCC_APB2ENR_AFIOEN_BIT) - -/* APB1 peripheral clock enable register */ - -#define RCC_APB1ENR_DACEN_BIT 29 -#define RCC_APB1ENR_BKPEN_BIT 27 -#define RCC_APB1ENR_PWREN_BIT 28 -#define RCC_APB1ENR_CANEN_BIT 25 -#define RCC_APB1ENR_USBEN_BIT 23 -#define RCC_APB1ENR_I2C2EN_BIT 22 -#define RCC_APB1ENR_I2C1EN_BIT 21 -#define RCC_APB1ENR_UART5EN_BIT 20 -#define RCC_APB1ENR_UART4EN_BIT 19 -#define RCC_APB1ENR_UART3EN_BIT 18 -#define RCC_APB1ENR_UART2EN_BIT 17 -#define RCC_APB1ENR_SPI3EN_BIT 15 -#define RCC_APB1ENR_SPI2EN_BIT 14 -#define RCC_APB1ENR_WWDGEN_BIT 11 -#define RCC_APB1ENR_TIM14EN_BIT 8 -#define RCC_APB1ENR_TIM13EN_BIT 7 -#define RCC_APB1ENR_TIM12EN_BIT 6 -#define RCC_APB1ENR_TIM7EN_BIT 5 -#define RCC_APB1ENR_TIM6EN_BIT 4 -#define RCC_APB1ENR_TIM5EN_BIT 3 -#define RCC_APB1ENR_TIM4EN_BIT 2 -#define RCC_APB1ENR_TIM3EN_BIT 1 -#define RCC_APB1ENR_TIM2EN_BIT 0 - -#define RCC_APB1ENR_DACEN BIT(RCC_APB1ENR_DACEN_BIT) -#define RCC_APB1ENR_PWREN BIT(RCC_APB1ENR_PWREN_BIT) -#define RCC_APB1ENR_BKPEN BIT(RCC_APB1ENR_BKPEN_BIT) -#define RCC_APB1ENR_CANEN BIT(RCC_APB1ENR_CANEN_BIT) -#define RCC_APB1ENR_USBEN BIT(RCC_APB1ENR_USBEN_BIT) -#define RCC_APB1ENR_I2C2EN BIT(RCC_APB1ENR_I2C2EN_BIT) -#define RCC_APB1ENR_I2C1EN BIT(RCC_APB1ENR_I2C1EN_BIT) -#define RCC_APB1ENR_UART5EN BIT(RCC_APB1ENR_UART5EN_BIT) -#define RCC_APB1ENR_UART4EN BIT(RCC_APB1ENR_UART4EN_BIT) -#define RCC_APB1ENR_UART3EN BIT(RCC_APB1ENR_UART3EN_BIT) -#define RCC_APB1ENR_UART2EN BIT(RCC_APB1ENR_UART2EN_BIT) -#define RCC_APB1ENR_SPI3EN BIT(RCC_APB1ENR_SPI3EN_BIT) -#define RCC_APB1ENR_SPI2EN BIT(RCC_APB1ENR_SPI2EN_BIT) -#define RCC_APB1ENR_WWDGEN BIT(RCC_APB1ENR_WWDGEN_BIT) -#define RCC_APB1ENR_TIM14EN BIT(RCC_APB1ENR_TIM14EN_BIT) -#define RCC_APB1ENR_TIM13EN BIT(RCC_APB1ENR_TIM13EN_BIT) -#define RCC_APB1ENR_TIM12EN BIT(RCC_APB1ENR_TIM12EN_BIT) -#define RCC_APB1ENR_TIM7EN BIT(RCC_APB1ENR_TIM7EN_BIT) -#define RCC_APB1ENR_TIM6EN BIT(RCC_APB1ENR_TIM6EN_BIT) -#define RCC_APB1ENR_TIM5EN BIT(RCC_APB1ENR_TIM5EN_BIT) -#define RCC_APB1ENR_TIM4EN BIT(RCC_APB1ENR_TIM4EN_BIT) -#define RCC_APB1ENR_TIM3EN BIT(RCC_APB1ENR_TIM3EN_BIT) -#define RCC_APB1ENR_TIM2EN BIT(RCC_APB1ENR_TIM2EN_BIT) - -/* Backup domain control register */ - -#define RCC_BDCR_BDRST_BIT 16 -#define RCC_BDCR_RTCEN_BIT 15 -#define RCC_BDCR_LSEBYP_BIT 2 -#define RCC_BDCR_LSERDY_BIT 1 -#define RCC_BDCR_LSEON_BIT 0 - -#define RCC_BDCR_BDRST BIT(RCC_BDCR_BDRST_BIT) -#define RCC_BDCR_RTCEN BIT(RCC_BDCR_RTCEN_BIT) -#define RCC_BDCR_RTCSEL (0x3 << 8) -#define RCC_BDCR_RTCSEL_LSE (0x1 << 8) -#define RCC_BDCR_RTCSEL_LSI (0x2 << 8) -#define RCC_BDCR_RTCSEL_HSE_DIV_128 (0x3 << 8) -#define RCC_BDCR_LSEBYP BIT(RCC_BDCR_LSEBYP_BIT) -#define RCC_BDCR_LSERDY BIT(RCC_BDCR_LSERDY_BIT) -#define RCC_BDCR_LSEON BIT(RCC_BDCR_LSEON_BIT) - -/* Control/status register */ - -#define RCC_CSR_LPWRRSTF_BIT 31 -#define RCC_CSR_WWDGRSTF_BIT 30 -#define RCC_CSR_IWDGRSTF_BIT 29 -#define RCC_CSR_SFTRSTF_BIT 28 -#define RCC_CSR_PORRSTF_BIT 27 -#define RCC_CSR_PINRSTF_BIT 26 -#define RCC_CSR_RMVF_BIT 25 -#define RCC_CSR_LSIRDY_BIT 1 -#define RCC_CSR_LSION_BIT 0 - -#define RCC_CSR_LPWRRSTF BIT(RCC_CSR_LPWRRSTF_BIT) -#define RCC_CSR_WWDGRSTF BIT(RCC_CSR_WWDGRSTF_BIT) -#define RCC_CSR_IWDGRSTF BIT(RCC_CSR_IWDGRSTF_BIT) -#define RCC_CSR_SFTRSTF BIT(RCC_CSR_SFTRSTF_BIT) -#define RCC_CSR_PORRSTF BIT(RCC_CSR_PORRSTF_BIT) -#define RCC_CSR_PINRSTF BIT(RCC_CSR_PINRSTF_BIT) -#define RCC_CSR_RMVF BIT(RCC_CSR_RMVF_BIT) -#define RCC_CSR_LSIRDY BIT(RCC_CSR_LSIRDY_BIT) -#define RCC_CSR_LSION BIT(RCC_CSR_LSION_BIT) - -/** - * Identifies bus and clock line for a device - */ -typedef enum { - RCC_SRAM, - RCC_GPIOA, - RCC_GPIOB, - RCC_GPIOC, - RCC_GPIOD, - RCC_AFIO, - RCC_ADC1, - RCC_ADC2, - RCC_USART1, - RCC_USART2, - RCC_USART3, - RCC_TIMER1, - RCC_TIMER2, - RCC_TIMER3, - RCC_TIMER4, - RCC_SPI1, - RCC_SPI2, - RCC_DMA1, - RCC_PWR, - RCC_BKP, - RCC_CAN, - RCC_USB, - RCC_I2C1, - RCC_I2C2, - RCC_CRC, - RCC_WWDG, - RCC_FLITF, -#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) - RCC_SDIO, - RCC_FSMC, - RCC_GPIOE, - RCC_GPIOF, - RCC_GPIOG, - RCC_ADC3, - RCC_UART4, - RCC_UART5, - RCC_TIMER5, - RCC_TIMER6, - RCC_TIMER7, - RCC_TIMER8, - RCC_DAC, - RCC_DMA2, - RCC_SPI3, -#endif -#ifdef STM32_XL_DENSITY - RCC_TIMER9, - RCC_TIMER10, - RCC_TIMER11, - RCC_TIMER12, - RCC_TIMER13, - RCC_TIMER14, -#endif -} rcc_clk_id; - -/* SYSCLK source */ +/* registers */ +#define RCC_BASE 0x40021000 +#define RCC_CR (RCC_BASE + 0x0) +#define RCC_CFGR (RCC_BASE + 0x4) +#define RCC_CIR (RCC_BASE + 0x8) +#define RCC_APB2RSTR (RCC_BASE + 0xC) +#define RCC_APB1RSTR (RCC_BASE + 0x10) +#define RCC_AHBENR (RCC_BASE + 0x14) +#define RCC_APB2ENR (RCC_BASE + 0x18) +#define RCC_APB1ENR (RCC_BASE + 0x1C) +#define RCC_BDCR (RCC_BASE + 0x20) +#define RCC_CSR (RCC_BASE + 0x24) +#define RCC_AHBSTR (RCC_BASE + 0x28) +#define RCC_CFGR2 (RCC_BASE + 0x2C) + +#define RCC_CFGR_USBPRE (0x1 << 22) +#define RCC_CFGR_ADCPRE (0x3 << 14) +#define RCC_CFGR_PPRE1 (0x7 << 8) +#define RCC_CFGR_PPRE2 (0x7 << 11) +#define RCC_CFGR_HPRE (0xF << 4) +#define RCC_CFGR_PLLSRC (0x1 << 16) + +#define RCC_CFGR_SWS (0x3 << 2) +#define RCC_CFGR_SWS_PLL (0x2 << 2) +#define RCC_CFGR_SWS_HSE (0x1 << 2) + +#define RCC_CFGR_SW (0x3 << 0) +#define RCC_CFGR_SW_PLL (0x2 << 0) +#define RCC_CFGR_SW_HSE (0x1 << 0) + +/* CR status bits */ +#define RCC_CR_HSEON (0x1 << 16) +#define RCC_CR_HSERDY (0x1 << 17) +#define RCC_CR_PLLON (0x1 << 24) +#define RCC_CR_PLLRDY (0x1 << 25) + +#define RCC_WRITE_CFGR(val) __write(RCC_CFGR, val) +#define RCC_READ_CFGR() __read(RCC_CFGR) + +#define RCC_WRITE_CR(val) __write(RCC_CR, val) +#define RCC_READ_CR() __read(RCC_CR) + +/* sysclk source */ #define RCC_CLKSRC_HSI (0x0) #define RCC_CLKSRC_HSE (0x1) #define RCC_CLKSRC_PLL (0x2) -/* ADC prescaler dividers */ +/* pll entry clock source */ +#define RCC_PLLSRC_HSE (0x1 << 16) +#define RCC_PLLSRC_HSI_DIV_2 (0x0 << 16) + +/* adc prescaler dividers */ #define RCC_ADCPRE_PCLK_DIV_2 (0x0 << 14) #define RCC_ADCPRE_PCLK_DIV_4 (0x1 << 14) #define RCC_ADCPRE_PCLK_DIV_6 (0x2 << 14) #define RCC_ADCPRE_PCLK_DIV_8 (0x3 << 14) -/* APB1 prescaler dividers */ +/* apb1 prescaler dividers */ #define RCC_APB1_HCLK_DIV_1 (0x0 << 8) #define RCC_APB1_HCLK_DIV_2 (0x4 << 8) #define RCC_APB1_HCLK_DIV_4 (0x5 << 8) #define RCC_APB1_HCLK_DIV_8 (0x6 << 8) #define RCC_APB1_HCLK_DIV_16 (0x7 << 8) -/* APB2 prescaler dividers */ +/* apb2 prescaler dividers */ #define RCC_APB2_HCLK_DIV_1 (0x0 << 11) #define RCC_APB2_HCLK_DIV_2 (0x4 << 11) #define RCC_APB2_HCLK_DIV_4 (0x5 << 11) #define RCC_APB2_HCLK_DIV_8 (0x6 << 11) #define RCC_APB2_HCLK_DIV_16 (0x7 << 11) -/* AHB prescaler dividers */ +/* ahb prescaler dividers */ #define RCC_AHB_SYSCLK_DIV_1 (0x0 << 4) #define RCC_AHB_SYSCLK_DIV_2 (0x8 << 4) #define RCC_AHB_SYSCLK_DIV_4 (0x9 << 4) @@ -492,19 +119,75 @@ typedef enum { #define RCC_AHB_SYSCLK_DIV_256 (0xE << 4) #define RCC_AHB_SYSCLK_DIV_512 (0xF << 4) -/* Prescalers */ -typedef enum rcc_prescaler { +/* pll multipliers */ +#define RCC_PLLMUL_2 (0x0 << 18) +#define RCC_PLLMUL_3 (0x1 << 18) +#define RCC_PLLMUL_4 (0x2 << 18) +#define RCC_PLLMUL_5 (0x3 << 18) +#define RCC_PLLMUL_6 (0x4 << 18) +#define RCC_PLLMUL_7 (0x5 << 18) +#define RCC_PLLMUL_8 (0x6 << 18) +#define RCC_PLLMUL_9 (0x7 << 18) +#define RCC_PLLMUL_10 (0x8 << 18) +#define RCC_PLLMUL_11 (0x9 << 18) +#define RCC_PLLMUL_12 (0xA << 18) +#define RCC_PLLMUL_13 (0xB << 18) +#define RCC_PLLMUL_14 (0xC << 18) +#define RCC_PLLMUL_15 (0xD << 18) +#define RCC_PLLMUL_16 (0xE << 18) + + +/* prescalers */ +enum { RCC_PRESCALER_AHB, RCC_PRESCALER_APB1, RCC_PRESCALER_APB2, RCC_PRESCALER_USB, RCC_PRESCALER_ADC -} rcc_prescaler; +}; + +/* + * Identifies bus and clock line for a device + */ +typedef enum { + RCC_GPIOA, + RCC_GPIOB, + RCC_GPIOC, + RCC_GPIOD, + RCC_GPIOE, // High-density devices only (Maple Native) + RCC_GPIOF, // High-density devices only (Maple Native) + RCC_GPIOG, // High-density devices only (Maple Native) + RCC_AFIO, + RCC_ADC1, + RCC_ADC2, + RCC_ADC3, + RCC_USART1, + RCC_USART2, + RCC_USART3, + RCC_UART4, // High-density devices only (Maple Native) + RCC_UART5, // High-density devices only (Maple Native) + RCC_TIMER1, + RCC_TIMER2, + RCC_TIMER3, + RCC_TIMER4, + RCC_TIMER5, // High-density devices only (Maple Native) + RCC_TIMER6, // High-density devices only (Maple Native) + RCC_TIMER7, // High-density devices only (Maple Native) + RCC_TIMER8, // High-density devices only (Maple Native) + RCC_SPI1, + RCC_SPI2, + RCC_FSMC, // High-density devices only (Maple Native) + RCC_DAC, // High-density devices only (Maple Native) + RCC_DMA1, + RCC_DMA2, // High-density devices only (Maple Native) + RCC_PWR, + RCC_BKP, +} rcc_clk_id; void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul); void rcc_clk_enable(rcc_clk_id device); void rcc_reset_dev(rcc_clk_id device); -void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider); +void rcc_set_prescaler(uint32 prescaler, uint32 divider); #ifdef __cplusplus } // extern "C" diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 66f008f..1256ba1 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -304,7 +304,7 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D98/PG5 */ {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, /* D99/PD10 */ - {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD} + {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD} }; #elif defined(BOARD_maple_mini) diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index c5a9e30..65d0262 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -53,7 +53,7 @@ void init(void) { #endif /* initialize clocks */ - rcc_clk_init(RCC_CLKSRC_PLL, RCC_CFGR_PLLSRC_HSE, RCC_CFGR_PLLMUL_9); + rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); -- cgit v1.2.3 From cf1f0fa96a6218739520c16bf6cd2c3df6ef97dd Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 21 Mar 2011 14:34:40 -0400 Subject: Native PIN_MAP typo --- wirish/boards.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 1256ba1..66f008f 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -304,7 +304,7 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = { /* D98/PG5 */ {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, /* D99/PD10 */ - {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD} + {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD} }; #elif defined(BOARD_maple_mini) -- cgit v1.2.3 From 61db54f52f32e63c895d775982fbcdcb67f2dde6 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 22 Mar 2011 16:59:29 -0400 Subject: Initial timer refactor. Basic PWM works. Had some problems in testing that might be due to USART bugs. HardwareTimer has been removed from the build for now; I will re-implement it in terms of the new libmaple API, but consider it deprecated. Let's come up with something better. Servo is implemented in terms of HardwareTimer, so it also has been temporarily removed from the build. pwmWrite() likely got a little bit less inefficient due to indirection, but the PIN_MAPs shrank by a pointer per PinMapping. --- Makefile | 2 +- examples/test-session.cpp | 19 +- examples/test-timers.cpp | 372 ++++++++------- libmaple/bitband.h | 5 + libmaple/delay.h | 2 +- libmaple/nvic.h | 101 ++-- libmaple/rules.mk | 2 +- libmaple/spi.h | 3 + libmaple/timer.c | 449 ++++++++++++++++++ libmaple/timer.h | 1010 ++++++++++++++++++++++++++++++++++++++++ libmaple/timers.c | 526 --------------------- libmaple/timers.h | 435 ----------------- libmaple/util.c | 2 +- libraries/Servo/Servo.h | 1 + notes/portable.txt | 94 +--- notes/usb.txt | 4 + notes/vga.txt | 9 +- wirish/boards.cpp | 646 +++++++++---------------- wirish/boards.h | 9 +- wirish/comm/HardwareSPI.cpp | 4 +- wirish/comm/HardwareSerial.cpp | 20 +- wirish/comm/HardwareSerial.h | 12 +- wirish/pwm.cpp | 22 +- wirish/rules.mk | 1 - wirish/wirish.cpp | 122 +++-- wirish/wirish.h | 3 - wirish/wirish_digital.cpp | 6 +- 27 files changed, 2095 insertions(+), 1786 deletions(-) create mode 100644 libmaple/timer.c create mode 100644 libmaple/timer.h delete mode 100644 libmaple/timers.c delete mode 100644 libmaple/timers.h (limited to 'wirish') diff --git a/Makefile b/Makefile index d31c9ed..109a126 100644 --- a/Makefile +++ b/Makefile @@ -97,7 +97,7 @@ endif LIBMAPLE_MODULES := $(SRCROOT)/libmaple LIBMAPLE_MODULES += $(SRCROOT)/wirish # Official libraries: -LIBMAPLE_MODULES += $(SRCROOT)/libraries/Servo +# LIBMAPLE_MODULES += $(SRCROOT)/libraries/Servo LIBMAPLE_MODULES += $(SRCROOT)/libraries/LiquidCrystal LIBMAPLE_MODULES += $(SRCROOT)/libraries/Wire diff --git a/examples/test-session.cpp b/examples/test-session.cpp index a147e06..9b4bce4 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -15,7 +15,6 @@ //#define COMM Serial2 //#define COMM Serial3 - #define ESC ((uint8)27) int rate = 0; @@ -610,17 +609,15 @@ void cmd_servo_sweep(void) { COMM.println("(reset serial port)"); } +static uint16 init_all_timers_prescale = 0; + +static void set_prescale(timer_dev *dev) { + timer_set_prescaler(dev, init_all_timers_prescale); +} + void init_all_timers(uint16 prescale) { - timer_init(TIMER1, prescale); - timer_init(TIMER2, prescale); - timer_init(TIMER3, prescale); - timer_init(TIMER4, prescale); -#ifdef STM32_HIGH_DENSITY - timer_init(TIMER5, prescale); - // timer_init(TIMER6, prescale); - // timer_init(TIMER7, prescale); - timer_init(TIMER8, prescale); -#endif + init_all_timers_prescale = prescale; + timer_foreach(set_prescale); } // Force init to be called *first*, i.e. before static object allocation. diff --git a/examples/test-timers.cpp b/examples/test-timers.cpp index f3cfdcc..a4fbc8a 100644 --- a/examples/test-timers.cpp +++ b/examples/test-timers.cpp @@ -1,8 +1,7 @@ -// Program to test the wirish timers implementation +// Program to test the timer.h implementation's essential functionality. #include "wirish.h" - -#define LED_PIN BOARD_LED_PIN +#include "timer.h" void handler1(void); void handler2(void); @@ -27,208 +26,253 @@ uint16 val2 = 10000; uint16 val3 = 10000; uint16 val4 = 10000; -HardwareTimer Timers[] = {Timer1, Timer2, Timer3, Timer4}; +// FIXME high density timer test (especially basic timers + DAC) +timer_dev *timers[] = {TIMER1, TIMER2, TIMER3, TIMER4}; +voidFuncPtr handlers[] = {handler1, handler2, handler3, handler4}; + +void initTimer(timer_dev *dev); +void setTimerPeriod(timer_dev *dev, uint32 period_us); +void testSetTimerPeriod(uint32 period); +void testTimerChannels(timer_dev *dev); +int timerNumber(timer_dev *dev); -void setup() -{ - /* Set up the LED to blink */ - pinMode(LED_PIN, OUTPUT); +void setup() { + // Set up the LED to blink + pinMode(BOARD_LED_PIN, OUTPUT); // Setup the button as input pinMode(BOARD_BUTTON_PIN, INPUT); - // Wait for user to attach... - waitForButtonPress(0); - - // Send a message out SerialUSB - SerialUSB.println("Beginning timer test..."); - for(int t=0; t<4; t++) { - Timers[t].setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel2Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel3Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel4Mode(TIMER_OUTPUTCOMPARE); - } + // Send a message out Serial2 + Serial2.begin(115200); + Serial2.println("*** Initializing timers..."); + Serial2.println("foo"); + timer_foreach(initTimer); + Serial2.println("*** Done. Beginning timer test."); } void loop() { - SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setCount/getCount"); - SerialUSB.print("Timer1.getCount() = "); SerialUSB.println(Timer1.getCount()); - SerialUSB.println("Timer1.setCount(1234)"); - Timer1.setCount(1234); - SerialUSB.print("Timer1.getCount() = "); SerialUSB.println(Timer1.getCount()); - // This tests whether the pause/resume functions work; when BUT is held - // down Timer4 is in the "pause" state and the timer doesn't increment, so - // the final counts should reflect the ratio of time that BUT was held down - SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing Pause/Resume; button roughly controls Timer4"); + Serial2.println("-----------------------------------------------------"); + + Serial2.println("Testing timer_get_count()/timer_set_count()"); + Serial2.print("TIMER1 count = "); + Serial2.println(timer_get_count(TIMER1)); + Serial2.println("timer_set_count(TIMER1, 1234)"); + timer_set_count(TIMER1, 1234); + Serial2.print("timer_get_count(TIMER1) = "); + Serial2.println(timer_get_count(TIMER1)); + + Serial2.println("-----------------------------------------------------"); + Serial2.println("Testing pause/resume; button roughly controls TIMER4"); + // when BUT is held down, TIMER4 is in the "pause" state and the + // timer doesn't increment, so the final counts should reflect the + // ratio of time that BUT was held down. count3 = 0; count4 = 0; - Timer3.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer3.pause(); - Timer4.pause(); - Timer3.setCount(0); - Timer4.setCount(0); - Timer3.setOverflow(30000); - Timer4.setOverflow(30000); - Timer3.setCompare1(1000); - Timer4.setCompare1(1000); - Timer3.attachCompare1Interrupt(handler3b); - Timer4.attachCompare1Interrupt(handler4b); - Timer3.resume(); - Timer4.resume(); - SerialUSB.println("~4 seconds..."); - for(int i = 0; i<4000; i++) { - if(isButtonPressed()) { - Timer4.pause(); + timer_set_mode(TIMER3, TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer_set_mode(TIMER4, TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer_pause(TIMER3); + timer_pause(TIMER4); + timer_set_count(TIMER3, 0); + timer_set_count(TIMER4, 0); + timer_set_reload(TIMER3, 30000); + timer_set_reload(TIMER4, 30000); + timer_set_compare(TIMER3, 1, 1000); + timer_set_compare(TIMER4, 1, 1000); + timer_attach_interrupt(TIMER3, TIMER_CC1_INTERRUPT, handler3b); + timer_attach_interrupt(TIMER4, TIMER_CC1_INTERRUPT, handler4b); + timer_resume(TIMER3); + timer_resume(TIMER4); + + Serial2.println("Testing for ~4 seconds..."); + for(int i = 0; i < 4000; i++) { + if (isButtonPressed()) { + timer_pause(TIMER4); } else { - Timer4.resume(); + timer_resume(TIMER4); } delay(1); } - Timer3.setChannel1Mode(TIMER_DISABLED); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count3: "); SerialUSB.println(count3); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - - // These test the setPeriod auto-configure functionality - SerialUSB.println("-----------------------------------------------------"); - SerialUSB.println("Testing setPeriod"); - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setCompare1(1); - Timer4.setPeriod(10); - Timer4.pause(); - Timer4.setCount(0); - Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 10ms, wait 2 seconds..."); - count4 = 0; - Timer4.resume(); - delay(2000); - Timer4.pause(); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - SerialUSB.println("(should be around 2sec/10ms = 200000)"); - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setCompare1(1); - Timer4.pause(); - Timer4.setPeriod(30000); - Timer4.setCount(0); - Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); - count4 = 0; - Timer4.resume(); - delay(2000); - Timer4.pause(); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - SerialUSB.println("(should be around 2sec/30000ms ~ 67)"); - - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setPeriod(300000); - Timer4.setCompare1(1); - Timer4.pause(); - Timer4.setCount(0); - Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 300000ms, wait 2 seconds..."); - count4 = 0; - Timer4.resume(); - delay(2000); - Timer4.pause(); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - SerialUSB.println("(should be around 2sec/300000ms ~ 6.7)"); - - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setPrescaleFactor(33); - Timer4.setOverflow(65454); - Timer4.pause(); - Timer4.setCount(0); - Timer4.setCompare1(1); - Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + + timer_set_mode(TIMER3, TIMER_CH1, TIMER_DISABLED); + timer_set_mode(TIMER4, TIMER_CH1, TIMER_DISABLED); + + Serial2.print("TIMER3 count: "); + Serial2.println(timer_get_count(TIMER3)); + Serial2.print("TIMER4 count: "); + Serial2.println(timer_get_count(TIMER4)); + + Serial2.println("-----------------------------------------------------"); + Serial2.println("Testing setTimerPeriod()"); + testSetTimerPeriod(10); + testSetTimerPeriod(30000); + testSetTimerPeriod(300000); + testSetTimerPeriod(30000); + + Serial2.println("Sanity check (with hand-coded reload and prescaler for " + "72 MHz timers):"); + timer_set_mode(TIMER4, TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer_set_prescaler(TIMER4, 33); + timer_set_reload(TIMER4, 65454); + timer_pause(TIMER4); + timer_set_count(TIMER4, 0); + timer_set_compare(TIMER4, TIMER_CH1, 1); + timer_attach_interrupt(TIMER4, TIMER_CC1_INTERRUPT, handler4b); + Serial2.println("Period 30000ms, wait 2 seconds..."); count4 = 0; - Timer4.resume(); + timer_resume(TIMER4); delay(2000); - Timer4.pause(); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - SerialUSB.println("(should be around 2sec/30000ms ~ 67)"); - - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setCompare1(1); - Timer4.setPeriod(30000); - Timer4.pause(); - Timer4.setCount(0); - Timer4.attachCompare1Interrupt(handler4b); - SerialUSB.println("Period 30000ms, wait 2 seconds..."); + timer_pause(TIMER4); + timer_set_mode(TIMER4, TIMER_CH1, TIMER_DISABLED); + Serial2.print("TIMER4 count: "); + Serial2.println(count4); + Serial2.println(" (Should be around 2sec/30000ms ~ 67)"); + + // Test all the individual timer channels + timer_foreach(testTimerChannels); +} + +void initTimer(timer_dev *dev) { + switch (dev->type) { + case TIMER_ADVANCED: + case TIMER_GENERAL: + Serial2.print("Initializing timer "); + Serial2.println(timerNumber(dev)); + for (int c = 1; c <= 4; c++) { + timer_set_mode(dev, c, TIMER_OUTPUT_COMPARE); + } + Serial2.println("Done."); + break; + case TIMER_BASIC: + break; + } +} + +void testSetTimerPeriod(uint32 period) { + timer_set_mode(TIMER4, TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer_set_compare(TIMER4, TIMER_CH1, 1); + setTimerPeriod(TIMER4, period); + timer_pause(TIMER4); + timer_set_count(TIMER4, 0); + timer_attach_interrupt(TIMER4, TIMER_CC1_INTERRUPT, handler4b); + Serial2.println("Period "); + Serial2.print(period); + Serial2.print(" ms. Waiting 2 seconds..."); count4 = 0; - Timer4.resume(); + timer_resume(TIMER4); delay(2000); - Timer4.pause(); - Timer4.setChannel1Mode(TIMER_DISABLED); - SerialUSB.print("Count4: "); SerialUSB.println(count4); - SerialUSB.println("(should be around 2sec/30000ms ~ 67)"); - - // This section is to touch every channel of every timer. The output - // ratios should reflect the ratios of the rate variables. Demonstrates - // that over time the actual timing rates get blown away by other system - // interrupts. - for(t=0; t<4; t++) { - toggleLED(); - delay(100); - SerialUSB.println("-----------------------------------------------------"); - SerialUSB.print("Testing Timer "); SerialUSB.println(t+1); + timer_pause(TIMER4); + timer_set_mode(TIMER4, TIMER_CH1, TIMER_DISABLED); + Serial2.print("TIMER4 count: "); + Serial2.println(timer_get_count(TIMER4)); + Serial2.print(" (Should be around 2 sec / "); + Serial2.print(period); + Serial2.print(" ms = "); + Serial2.print(double(2) / period * 1000); + Serial2.println(", modulo delays due to interrupts)"); +} + +int timerNumber(timer_dev *dev) { + switch (dev->clk_id) { + case RCC_TIMER1: + return 1; + case RCC_TIMER2: + return 2; + case RCC_TIMER3: + return 3; + case RCC_TIMER4: + return 4; +#ifdef STM32_HIGH_DENSITY + case RCC_TIMER5: + return 5; + case RCC_TIMER6: + return 6; + case RCC_TIMER7: + return 7; + case RCC_TIMER8: + return 8; +#endif + default: + ASSERT(0); + return 0; + } +} + +/* This function touches every channel of a given timer. The output + * ratios should reflect the ratios of the rate variables. It + * demonstrates that, over time, the actual timing rates get blown + * away by other system interrupts. */ +void testTimerChannels(timer_dev *dev) { + t = timerNumber(dev); + toggleLED(); + delay(100); + Serial2.println("-----------------------------------------------------"); + switch (dev->type) { + case TIMER_BASIC: + Serial2.print("NOT testing channels for basic timer "); + Serial2.println(t); + break; + case TIMER_ADVANCED: + case TIMER_GENERAL: + Serial2.print("Testing channels for timer "); + Serial2.println(t); + timer_pause(dev); count1 = count2 = count3 = count4 = 0; - Timers[t].setOverflow(0xFFFF); - Timers[t].setPrescaleFactor(1); - Timers[t].setCompare1(65535); - Timers[t].setCompare2(65535); - Timers[t].setCompare3(65535); - Timers[t].setCompare4(65535); - Timers[t].setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel2Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel3Mode(TIMER_OUTPUTCOMPARE); - Timers[t].setChannel4Mode(TIMER_OUTPUTCOMPARE); - Timers[t].attachCompare1Interrupt(handler1); - Timers[t].attachCompare2Interrupt(handler2); - Timers[t].attachCompare3Interrupt(handler3); - Timers[t].attachCompare4Interrupt(handler4); - Timers[t].resume(); + timer_set_reload(dev, 0xFFFF); + timer_set_prescaler(dev, 1); + for (int c = 1; c <= 4; c++) { + timer_set_compare(dev, c, 65535); + timer_set_mode(dev, c, TIMER_OUTPUT_COMPARE); + timer_attach_interrupt(dev, c, handlers[c - 1]); + } + timer_resume(dev); delay(3000); - Timers[t].setChannel1Mode(TIMER_DISABLED); - Timers[t].setChannel2Mode(TIMER_DISABLED); - Timers[t].setChannel3Mode(TIMER_DISABLED); - Timers[t].setChannel4Mode(TIMER_DISABLED); - SerialUSB.print("Count1: "); SerialUSB.println(count1); - SerialUSB.print("Count2: "); SerialUSB.println(count2); - SerialUSB.print("Count3: "); SerialUSB.println(count3); - SerialUSB.print("Count4: "); SerialUSB.println(count4); + for (int c = 1; c <= 4; c++) { + timer_set_mode(dev, c, TIMER_DISABLED); + } + Serial2.print("Channel 1 count: "); Serial2.println(count1); + Serial2.print("Channel 2 count: "); Serial2.println(count2); + Serial2.print("Channel 3 count: "); Serial2.println(count3); + Serial2.print("Channel 4 count: "); Serial2.println(count4); + break; + } +} + +// FIXME move this into the new wirish timer implementation +void setTimerPeriod(timer_dev *dev, uint32 period_us) { + if (!period_us) { + // FIXME handle this case + ASSERT(0); + return; } + uint32 cycles = period_us * CYCLES_PER_MICROSECOND; + uint16 pre = (uint16)((cycles >> 16) + 1); + timer_set_prescaler(dev, pre); + timer_set_reload(dev, cycles / pre - 1); } void handler1(void) { val1 += rate1; - Timers[t].setCompare1(val1); + timer_set_compare(timers[t], TIMER_CH1, val1); count1++; } void handler2(void) { val2 += rate2; - Timers[t].setCompare2(val2); + timer_set_compare(timers[t], TIMER_CH2, val2); count2++; } void handler3(void) { val3 += rate3; - Timers[t].setCompare3(val3); + timer_set_compare(timers[t], TIMER_CH3, val3); count3++; } void handler4(void) { val4 += rate4; - Timers[t].setCompare4(val4); + timer_set_compare(timers[t], TIMER_CH4, val4); count4++; } diff --git a/libmaple/bitband.h b/libmaple/bitband.h index 3e02702..870abe9 100644 --- a/libmaple/bitband.h +++ b/libmaple/bitband.h @@ -30,6 +30,9 @@ * @brief Bit-banding utility functions */ +#ifndef _BITBAND_H_ +#define _BITBAND_H_ + #define BB_SRAM_REF 0x20000000 #define BB_SRAM_BASE 0x22000000 #define BB_PERI_REF 0x40000000 @@ -103,3 +106,5 @@ static inline __io uint32* __bb_addr(__io void *address, uint32 bb_ref) { return (__io uint32*)(bb_base + ((uint32)address - bb_ref) * 32 + bit * 4); } + +#endif /* _BITBAND_H_ */ diff --git a/libmaple/delay.h b/libmaple/delay.h index 10839c9..e4d85c5 100644 --- a/libmaple/delay.h +++ b/libmaple/delay.h @@ -1,5 +1,5 @@ /** - * @brief + * @brief Delay implementation */ #ifndef _DELAY_H_ diff --git a/libmaple/nvic.h b/libmaple/nvic.h index fe9990f..cbcd49c 100644 --- a/libmaple/nvic.h +++ b/libmaple/nvic.h @@ -53,9 +53,6 @@ extern "C"{ /* System control registers */ #define SCB_VTOR 0xE000ED08 // Vector table offset register -#define NVIC_VectTab_RAM ((u32)0x20000000) -#define NVIC_VectTab_FLASH ((u32)0x08000000) - #define NVIC_BASE 0xE000E100 #define NVIC ((nvic_reg_map*)NVIC_BASE) @@ -75,52 +72,58 @@ typedef struct nvic_reg_map { __io uint32 STIR; // Software Trigger Interrupt Registers } nvic_reg_map; -enum { - NVIC_NMI = -14, - NVIC_MEM_MANAGE = -12, - NVIC_BUS_FAULT = -11, - NVIC_USAGE_FAULT = -10, - NVIC_SVC = -5, - NVIC_DEBUG_MON = -4, - NVIC_PEND_SVC = -2, - NVIC_SYSTICK = -1, - NVIC_TIMER1 = 27, - NVIC_TIMER2 = 28, - NVIC_TIMER3 = 29, - NVIC_TIMER4 = 30, - NVIC_TIMER5 = 50, // high density only (Maple Native, Maple Audio) - NVIC_TIMER6 = 54, // high density only - NVIC_TIMER7 = 55, // high density only - NVIC_TIMER8 = 46, // high density only - - NVIC_USART1 = 37, - NVIC_USART2 = 38, - NVIC_USART3 = 39, - NVIC_UART4 = 52, // high density only - NVIC_UART5 = 53, // high density only - - NVIC_EXTI0 = 6, - NVIC_EXTI1 = 7, - NVIC_EXTI2 = 8, - NVIC_EXTI3 = 9, - NVIC_EXTI4 = 10, - NVIC_EXTI9_5 = 23, - NVIC_EXTI15_10 = 40, - - NVIC_DMA_CH1 = 11, - NVIC_DMA_CH2 = 12, - NVIC_DMA_CH3 = 13, - NVIC_DMA_CH4 = 14, - NVIC_DMA_CH5 = 15, - NVIC_DMA_CH6 = 16, - NVIC_DMA_CH7 = 17, - - NVIC_I2C1_EV = 31, - NVIC_I2C1_ER = 32, - NVIC_I2C2_EV = 33, - NVIC_I2C2_ER = 34 -}; - +typedef enum nvic_irq_num { + NVIC_NMI = -14, + NVIC_MEM_MANAGE = -12, + NVIC_BUS_FAULT = -11, + NVIC_USAGE_FAULT = -10, + NVIC_SVC = -5, + NVIC_DEBUG_MON = -4, + NVIC_PEND_SVC = -2, + NVIC_SYSTICK = -1, + + NVIC_TIMER1_BRK = 24, + NVIC_TIMER1_UP = 25, + NVIC_TIMER1_TRG_COM = 26, + NVIC_TIMER1_CC = 27, + NVIC_TIMER2 = 28, + NVIC_TIMER3 = 29, + NVIC_TIMER4 = 30, + NVIC_TIMER5 = 50, + NVIC_TIMER6 = 54, + NVIC_TIMER7 = 55, + NVIC_TIMER8_BRK = 43, + NVIC_TIMER8_UP = 44, + NVIC_TIMER8_TRG_COM = 45, + NVIC_TIMER8_CC = 46, + + NVIC_USART1 = 37, + NVIC_USART2 = 38, + NVIC_USART3 = 39, + NVIC_UART4 = 52, + NVIC_UART5 = 53, + + NVIC_EXTI0 = 6, + NVIC_EXTI1 = 7, + NVIC_EXTI2 = 8, + NVIC_EXTI3 = 9, + NVIC_EXTI4 = 10, + NVIC_EXTI9_5 = 23, + NVIC_EXTI15_10 = 40, + + NVIC_DMA_CH1 = 11, + NVIC_DMA_CH2 = 12, + NVIC_DMA_CH3 = 13, + NVIC_DMA_CH4 = 14, + NVIC_DMA_CH5 = 15, + NVIC_DMA_CH6 = 16, + NVIC_DMA_CH7 = 17, + + NVIC_I2C1_EV = 31, + NVIC_I2C1_ER = 32, + NVIC_I2C2_EV = 33, + NVIC_I2C2_ER = 34 +} nvic_irq_num; #define nvic_globalirq_enable() asm volatile("cpsie i") #define nvic_globalirq_disable() asm volatile("cpsid i") diff --git a/libmaple/rules.mk b/libmaple/rules.mk index 48b5ed4..a9d7e50 100644 --- a/libmaple/rules.mk +++ b/libmaple/rules.mk @@ -28,7 +28,7 @@ cSRCS_$(d) := adc.c \ spi.c \ syscalls.c \ systick.c \ - timers.c \ + timer.c \ usart.c \ util.c \ usb/descriptors.c \ diff --git a/libmaple/spi.h b/libmaple/spi.h index db8aa9c..5ebf52d 100644 --- a/libmaple/spi.h +++ b/libmaple/spi.h @@ -31,6 +31,9 @@ #ifndef _SPI_H_ #define _SPI_H_ +#include "libmaple_types.h" +#include "util.h" + #ifdef __cplusplus extern "C" { #endif diff --git a/libmaple/timer.c b/libmaple/timer.c new file mode 100644 index 0000000..ad0ec6f --- /dev/null +++ b/libmaple/timer.c @@ -0,0 +1,449 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file timer.c + * @author Marti Bolivar + * @brief New-style timer interface + */ + +#include "timer.h" + +#if defined(STM32_MEDIUM_DENSITY) +#define NR_TIMERS 4 +#elif defined(STM32_HIGH_DENSITY) +#define NR_TIMERS 8 +#endif + +/* Just like the corresponding DIER bits: + * [0] = Update handler; + * [1,2,3,4] = capture/compare 1,2,3,4 handlers, respectively; + * [5] = COM; + * [6] = TRG; + * [7] = BRK. */ +#define NR_ADV_HANDLERS 8 +/* Update, capture/compare 1,2,3,4; ; trigger. */ +#define NR_GEN_HANDLERS 6 +/* Update only. */ +#define NR_BAS_HANDLERS 1 + +static timer_dev timer1 = { + .regs = {.adv = TIMER1_BASE}, + .clk_id = RCC_TIMER1, + .type = TIMER_ADVANCED, + .handlers = { [NR_ADV_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER1 = &timer1; + +static timer_dev timer2 = { + .regs = {.gen = TIMER2_BASE}, + .clk_id = RCC_TIMER2, + .type = TIMER_GENERAL, + .handlers = { [NR_GEN_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER2 = &timer2; + +static timer_dev timer3 = { + .regs = {.gen = TIMER3_BASE}, + .clk_id = RCC_TIMER3, + .type = TIMER_GENERAL, + .handlers = { [NR_GEN_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER3 = &timer3; + +static timer_dev timer4 = { + .regs = {.gen = TIMER4_BASE}, + .clk_id = RCC_TIMER4, + .type = TIMER_GENERAL, + .handlers = { [NR_GEN_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER4 = &timer4; + +#ifdef STM32_HIGH_DENSITY +static timer_dev timer5 = { + .regs = {.gen = TIMER5_BASE}, + .clk_id = RCC_TIMER5, + .type = TIMER_GENERAL, + .handlers = { [NR_GEN_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER5 = &timer5; + +static timer_dev timer6 = { + .regs = {.bas = TIMER6_BASE}, + .clk_id = RCC_TIMER6, + .type = TIMER_BASIC, + .handlers = { [NR_BAS_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER6 = &timer6; + +static timer_dev timer7 = { + .regs = {.bas = TIMER7_BASE}, + .clk_id = RCC_TIMER7, + .type = TIMER_BASIC, + .handlers = { [NR_BAS_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER7 = &timer7; + +static timer_dev timer8 = { + .regs = {.adv = TIMER8_BASE}, + .clk_id = RCC_TIMER8, + .type = TIMER_ADVANCED, + .handlers = { [NR_ADV_HANDLERS - 1] = 0 }, +}; +timer_dev *TIMER8 = &timer8; +#endif + +/* + * Convenience routines + */ + +static void disable_channel(timer_dev *dev, uint8 channel); +static void pwm_mode(timer_dev *dev, uint8 channel); +static void output_compare_mode(timer_dev *dev, uint8 channel); + +static inline void enable_irq(timer_dev *dev, uint8 interrupt); + +/** + * Initialize a timer, and reset its register map. + * @param dev Timer to initialize + */ +void timer_init(timer_dev *dev) { + rcc_clk_enable(dev->clk_id); + rcc_reset_dev(dev->clk_id); +} + +/** + * @brief Disable a timer. + * + * The timer will stop counting, all DMA requests and interrupts will + * be disabled, and no state changes will be output. + * + * @param dev Timer to disable. + */ +void timer_disable(timer_dev *dev) { + (dev->regs).bas->CR1 = 0; + (dev->regs).bas->DIER = 0; + switch (dev->type) { + case TIMER_ADVANCED: /* fall-through */ + case TIMER_GENERAL: + (dev->regs).gen->CCER = 0; + break; + case TIMER_BASIC: + break; + } +} + +/** + * Sets the mode of an individual timer channel. + * + * Note that not all timers can be configured in every mode. For + * example, basic timers cannot be configured to output compare mode. + * Be sure to use a timer which is appropriate for the mode you want. + * + * @param dev Timer whose channel mode to set + * @param channel Relevant channel + * @param mode New timer mode for channel + */ +void timer_set_mode(timer_dev *dev, uint8 channel, timer_mode mode) { + ASSERT(channel > 0 && channel <= 4); + + /* TODO decide about the basic timers */ + ASSERT(dev->type != TIMER_BASIC); + if (dev->type == TIMER_BASIC) + return; + + switch (mode) { + case TIMER_DISABLED: + disable_channel(dev, channel); + break; + case TIMER_PWM: + pwm_mode(dev, channel); + break; + case TIMER_OUTPUT_COMPARE: + output_compare_mode(dev, channel); + break; + } +} + +/** + * @brief Call a given function on all timers. + * @param fn Function to call on each timer. + */ +void timer_foreach(void (*fn)(timer_dev*)) { + fn(TIMER1); + fn(TIMER2); + fn(TIMER3); + fn(TIMER4); +#ifdef STM32_HIGH_DENSITY + fn(TIMER5); + fn(TIMER6); + fn(TIMER7); + fn(TIMER8); +#endif +} + +/** + * @brief Attach a timer interrupt. + * @param dev Timer device + * @param interrupt Interrupt number to attach to; this may be any + * timer_interrupt_id or timer_channel value appropriate + * for the timer. + * @param handler Handler to attach to the given interrupt. + * @see timer_interrupt_id + * @see timer_channel + */ +void timer_attach_interrupt(timer_dev *dev, + uint8 interrupt, + voidFuncPtr handler) { + dev->handlers[interrupt] = handler; + timer_enable_interrupt(dev, interrupt); + enable_irq(dev, interrupt); +} + +/** + * @brief Detach a timer interrupt. + * @param dev Timer device + * @param interrupt Interrupt number to detach; this may be any + * timer_interrupt_id or timer_channel value appropriate + * for the timer. + * @see timer_interrupt_id + * @see timer_channel + */ +void timer_detach_interrupt(timer_dev *dev, uint8 interrupt) { + timer_disable_interrupt(dev, interrupt); + dev->handlers[interrupt] = NULL; +} + +/* + * IRQ handlers + */ + +static inline void dispatch_adv_brk(timer_dev *dev); +static inline void dispatch_adv_up(timer_dev *dev); +static inline void dispatch_adv_trg_com(timer_dev *dev); +static inline void dispatch_adv_cc(timer_dev *dev); +static inline void dispatch_general(timer_dev *dev); +static inline void dispatch_basic(timer_dev *dev); + +void __irq_tim1_brk(void) { + dispatch_adv_brk(TIMER1); +} + +void __irq_tim1_up(void) { + dispatch_adv_up(TIMER1); +} + +void __irq_tim1_trg_com(void) { + dispatch_adv_trg_com(TIMER1); +} + +void __irq_tim1_cc(void) { + dispatch_adv_cc(TIMER1); +} + +void __irq_tim2(void) { + dispatch_general(TIMER2); +} + +void __irq_tim3(void) { + dispatch_general(TIMER3); +} + +void __irq_tim4(void) { + dispatch_general(TIMER4); +} + +#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + +void __irq_tim5(void) { + dispatch_general(TIMER5); +} + +void __irq_tim6(void) { + dispatch_basic(TIMER6); +} + +void __irq_tim7(void) { + dispatch_basic(TIMER7); +} + +void __irq_tim8_brk(void) { + dispatch_adv_brk(TIMER8); +} + +void __irq_tim8_up(void) { + dispatch_adv_up(TIMER8); +} + +void __irq_tim8_trg_com(void) { + dispatch_adv_trg_com(TIMER8); +} + +void __irq_tim8_cc(void) { + dispatch_adv_cc(TIMER8); +} +#endif + +static inline void dispatch_irq(timer_dev *dev, uint8 iid, uint8 sr_bit); +static inline void dispatch_cc_irqs(timer_dev *dev); + +static inline void dispatch_adv_brk(timer_dev *dev) { + dispatch_irq(dev, TIMER_BREAK_INTERRUPT, TIMER_SR_BIF_BIT); +} + +static inline void dispatch_adv_up(timer_dev *dev) { + dispatch_irq(dev, TIMER_UPDATE_INTERRUPT, TIMER_SR_UIF_BIT); +} + +static inline void dispatch_adv_trg_com(timer_dev *dev) { + dispatch_irq(dev, TIMER_TRG_INTERRUPT, TIMER_SR_TIF_BIT); + dispatch_irq(dev, TIMER_COM_INTERRUPT, TIMER_SR_COMIF_BIT); +} + +static inline void dispatch_adv_cc(timer_dev *dev) { + dispatch_cc_irqs(dev); +} + +static inline void dispatch_general(timer_dev *dev) { + dispatch_irq(dev, TIMER_TRG_INTERRUPT, TIMER_SR_TIF_BIT); + dispatch_cc_irqs(dev); + dispatch_irq(dev, TIMER_UPDATE_INTERRUPT, TIMER_SR_UIF_BIT); +} + +static inline void dispatch_basic(timer_dev *dev) { + dispatch_irq(dev, TIMER_UPDATE_INTERRUPT, TIMER_SR_UIF_BIT); +} + +static inline void dispatch_irq(timer_dev *dev, uint8 iid, uint8 sr_bit) { + __io uint32 *sr = &(dev->regs).bas->SR; + if (bb_peri_get_bit(sr, sr_bit)) { + if (dev->handlers[iid]) + (dev->handlers[iid])(); + bb_peri_set_bit(sr, sr_bit, 0); + } +} + +static inline void dispatch_cc_irqs(timer_dev *dev) { + uint32 sr = (dev->regs).gen->SR; + uint32 sr_clear = 0; + uint32 b; + + ASSERT(sr & (TIMER_SR_CC1IF | TIMER_SR_CC2IF | + TIMER_SR_CC3IF | TIMER_SR_CC4IF)); + + for (b = TIMER_SR_CC1IF_BIT; b <= TIMER_SR_CC4IF_BIT; b++) { + uint32 mask = BIT(b); + if (sr & mask) { + if (dev->handlers[b]) + (dev->handlers[b])(); + sr_clear |= mask; + } + } + + (dev->regs).gen->SR &= ~sr_clear; +} + +/* + * Utilities + */ + +static void disable_channel(timer_dev *dev, uint8 channel) { + timer_detach_interrupt(dev, channel); + timer_cc_disable(dev, channel); +} + +static void pwm_mode(timer_dev *dev, uint8 channel) { + timer_disable_interrupt(dev, channel); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, TIMER_OC_PE); + timer_cc_enable(dev, channel); +} + +static void output_compare_mode(timer_dev *dev, uint8 channel) { + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_ACTIVE_ON_MATCH, 0); + timer_cc_enable(dev, channel); +} + +static void enable_advanced_irq(timer_dev *dev, timer_interrupt_id id); +static void enable_nonmuxed_irq(timer_dev *dev); + +static inline void enable_irq(timer_dev *dev, timer_interrupt_id iid) { + if (dev->type == TIMER_ADVANCED) { + enable_advanced_irq(dev, iid); + } else { + enable_nonmuxed_irq(dev); + } +} + +static void enable_advanced_irq(timer_dev *dev, timer_interrupt_id id) { + uint8 is_timer1 = dev->clk_id == RCC_TIMER1; + + switch (id) { + case TIMER_UPDATE_INTERRUPT: + nvic_irq_enable(is_timer1 ? NVIC_TIMER1_UP : NVIC_TIMER8_UP); + break; + case TIMER_CC1_INTERRUPT: + case TIMER_CC2_INTERRUPT: + case TIMER_CC3_INTERRUPT: + case TIMER_CC4_INTERRUPT: + nvic_irq_enable(is_timer1 ? NVIC_TIMER1_CC : NVIC_TIMER8_CC); + break; + case TIMER_COM_INTERRUPT: + case TIMER_TRG_INTERRUPT: + nvic_irq_enable(is_timer1 ? NVIC_TIMER1_TRG_COM : NVIC_TIMER8_TRG_COM); + break; + case TIMER_BREAK_INTERRUPT: + nvic_irq_enable(is_timer1 ? NVIC_TIMER1_BRK : NVIC_TIMER8_BRK); + break; + } +} + +static void enable_nonmuxed_irq(timer_dev *dev) { + switch (dev->clk_id) { + case RCC_TIMER2: + nvic_irq_enable(NVIC_TIMER2); + break; + case RCC_TIMER3: + nvic_irq_enable(NVIC_TIMER3); + break; + case RCC_TIMER4: + nvic_irq_enable(NVIC_TIMER4); + break; +#ifdef STM32_HIGH_DENSITY + case RCC_TIMER5: + nvic_irq_enable(NVIC_TIMER5); + break; + case RCC_TIMER6: + nvic_irq_enable(NVIC_TIMER6); + break; + case RCC_TIMER7: + nvic_irq_enable(NVIC_TIMER7); + break; +#endif + default: + ASSERT(0); + break; + } +} diff --git a/libmaple/timer.h b/libmaple/timer.h new file mode 100644 index 0000000..025bcb0 --- /dev/null +++ b/libmaple/timer.h @@ -0,0 +1,1010 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file timer.h + * @author Marti Bolivar + * @brief New-style timer interface. + * + * Replaces old timers.h implementation. + */ + +#ifndef _TIMERS_H_ +#define _TIMERS_H_ + +#include "libmaple.h" +#include "rcc.h" +#include "nvic.h" +#include "bitband.h" + +#ifdef __cplusplus +extern "C"{ +#endif + +/* + * Register maps and devices + */ + +/** Advanced control timer register map type */ +typedef struct timer_adv_reg_map { + __io uint32 CR1; /**< Control register 1 */ + __io uint32 CR2; /**< Control register 2 */ + __io uint32 SMCR; /**< Slave mode control register */ + __io uint32 DIER; /**< DMA/Interrupt enable register */ + __io uint32 SR; /**< Status register */ + __io uint32 EGR; /**< Event generation register */ + __io uint32 CCMR1; /**< Capture/compare mode register 1 */ + __io uint32 CCMR2; /**< Capture/compare mode register 2 */ + __io uint32 CCER; /**< Capture/compare enable register */ + __io uint32 CNT; /**< Counter */ + __io uint32 PSC; /**< Prescaler */ + __io uint32 ARR; /**< Auto-reload register */ + __io uint32 RCR; /**< Repetition counter register */ + __io uint32 CCR1; /**< Capture/compare register 1 */ + __io uint32 CCR2; /**< Capture/compare register 2 */ + __io uint32 CCR3; /**< Capture/compare register 3 */ + __io uint32 CCR4; /**< Capture/compare register 4 */ + __io uint32 BDTR; /**< Break and dead-time register */ + __io uint32 DCR; /**< DMA control register */ + __io uint32 DMAR; /**< DMA address for full transfer */ +} timer_adv_reg_map; + +/** General purpose timer register map type */ +typedef struct timer_gen_reg_map { + __io uint32 CR1; /**< Control register 1 */ + __io uint32 CR2; /**< Control register 2 */ + __io uint32 SMCR; /**< Slave mode control register */ + __io uint32 DIER; /**< DMA/Interrupt enable register */ + __io uint32 SR; /**< Status register */ + __io uint32 EGR; /**< Event generation register */ + __io uint32 CCMR1; /**< Capture/compare mode register 1 */ + __io uint32 CCMR2; /**< Capture/compare mode register 2 */ + __io uint32 CCER; /**< Capture/compare enable register */ + __io uint32 CNT; /**< Counter */ + __io uint32 PSC; /**< Prescaler */ + __io uint32 ARR; /**< Auto-reload register */ + const uint32 RESERVED1; /**< Reserved */ + __io uint32 CCR1; /**< Capture/compare register 1 */ + __io uint32 CCR2; /**< Capture/compare register 2 */ + __io uint32 CCR3; /**< Capture/compare register 3 */ + __io uint32 CCR4; /**< Capture/compare register 4 */ + const uint32 RESERVED2; /**< Reserved */ + __io uint32 DCR; /**< DMA control register */ + __io uint32 DMAR; /**< DMA address for full transfer */ +} timer_gen_reg_map; + +/** Basic timer register map type */ +typedef struct timer_bas_reg_map { + __io uint32 CR1; /**< Control register 1 */ + __io uint32 CR2; /**< Control register 2 */ + const uint32 RESERVED1; /**< Reserved */ + __io uint32 DIER; /**< DMA/Interrupt enable register */ + __io uint32 SR; /**< Status register */ + __io uint32 EGR; /**< Event generation register */ + const uint32 RESERVED2; /**< Reserved */ + const uint32 RESERVED3; /**< Reserved */ + const uint32 RESERVED4; /**< Reserved */ + __io uint32 CNT; /**< Counter */ + __io uint32 PSC; /**< Prescaler */ + __io uint32 ARR; /**< Auto-reload register */ +} timer_bas_reg_map; + +/** Timer 1 register map base pointer */ +#define TIMER1_BASE ((struct timer_adv_reg_map*)0x40012C00) +/** Timer 2 register map base pointer */ +#define TIMER2_BASE ((struct timer_gen_reg_map*)0x40000000) +/** Timer 3 register map base pointer */ +#define TIMER3_BASE ((struct timer_gen_reg_map*)0x40000400) +/** Timer 4 register map base pointer */ +#define TIMER4_BASE ((struct timer_gen_reg_map*)0x40000800) +#ifdef STM32_HIGH_DENSITY +/** Timer 5 register map base pointer */ +#define TIMER5_BASE ((struct timer_gen_reg_map*)0x40000C00) +/** Timer 6 register map base pointer */ +#define TIMER6_BASE ((struct timer_bas_reg_map*)0x40001000) +/** Timer 7 register map base pointer */ +#define TIMER7_BASE ((struct timer_bas_reg_map*)0x40001400) +/** Timer 8 register map base pointer */ +#define TIMER8_BASE ((struct timer_adv_reg_map*)0x40013400) +#endif + +/* + * Timer devices + */ + +typedef union { + timer_adv_reg_map *adv; + timer_gen_reg_map *gen; + timer_bas_reg_map *bas; +} timer_reg_map_union; + +typedef enum { + TIMER_ADVANCED, + TIMER_GENERAL, + TIMER_BASIC +} timer_type; + +/** Timer device type */ +typedef struct timer_dev { + timer_reg_map_union regs; + rcc_clk_id clk_id; + timer_type type; + voidFuncPtr handlers[]; +} timer_dev; + +/** Timer 1 device (advanced) */ +extern timer_dev *TIMER1; +/** Timer 2 device (general-purpose) */ +extern timer_dev *TIMER2; +/** Timer 3 device (general-purpose) */ +extern timer_dev *TIMER3; +/** Timer 4 device (general-purpose) */ +extern timer_dev *TIMER4; +#ifdef STM32_HIGH_DENSITY +/** Timer 5 device (general-purpose) */ +extern timer_dev *TIMER5; +/** Timer 6 device (basic) */ +extern timer_dev *TIMER6; +/** Timer 7 device (basic) */ +extern timer_dev *TIMER7; +/** Timer 8 device (basic) */ +extern timer_dev *TIMER8; +#endif + +/* + * Register bit definitions + */ + +/* Control register 1 (CR1) */ + +#define TIMER_CR1_ARPE_BIT 7 +#define TIMER_CR1_DIR_BIT 4 +#define TIMER_CR1_OPM_BIT 3 +#define TIMER_CR1_URS_BIT 2 +#define TIMER_CR1_UDIS_BIT 1 +#define TIMER_CR1_CEN_BIT 0 + +#define TIMER_CR1_CKD (0x3 << 8) +#define TIMER_CR1_CKD_1TCKINT (0x0 << 8) +#define TIMER_CR1_CKD_2TCKINT (0x1 << 8) +#define TIMER_CR1_CKD_4TICKINT (0x2 << 8) +#define TIMER_CR1_ARPE BIT(TIMER_CR1_ARPE_BIT) +#define TIMER_CR1_CKD_CMS (0x3 << 5) +#define TIMER_CR1_CKD_CMS_EDGE (0x0 << 5) +#define TIMER_CR1_CKD_CMS_CENTER1 (0x1 << 5) +#define TIMER_CR1_CKD_CMS_CENTER2 (0x2 << 5) +#define TIMER_CR1_CKD_CMS_CENTER3 (0x3 << 5) +#define TIMER_CR1_DIR BIT(TIMER_CR1_DIR_BIT) +#define TIMER_CR1_OPM BIT(TIMER_CR1_OPM_BIT) +#define TIMER_CR1_URS BIT(TIMER_CR1_URS_BIT) +#define TIMER_CR1_UDIS BIT(TIMER_CR1_UDIS_BIT) +#define TIMER_CR1_CEN BIT(TIMER_CR1_CEN_BIT) + +/* Control register 2 (CR2) */ + +#define TIMER_CR2_OIS4_BIT 14 +#define TIMER_CR2_OIS3N_BIT 13 +#define TIMER_CR2_OIS3_BIT 12 +#define TIMER_CR2_OIS2N_BIT 11 +#define TIMER_CR2_OIS2_BIT 10 +#define TIMER_CR2_OIS1N_BIT 9 +#define TIMER_CR2_OIS1_BIT 8 +#define TIMER_CR2_TI1S_BIT 7 /* tills? yikes */ +#define TIMER_CR2_CCDS_BIT 3 +#define TIMER_CR2_CCUS_BIT 2 +#define TIMER_CR2_CCPC_BIT 0 + +#define TIMER_CR2_OIS4 BIT(TIMER_CR2_OIS4_BIT) +#define TIMER_CR2_OIS3N BIT(TIMER_CR2_OIS3N_BIT) +#define TIMER_CR2_OIS3 BIT(TIMER_CR2_OIS3_BIT) +#define TIMER_CR2_OIS2N BIT(TIMER_CR2_OIS2N_BIT) +#define TIMER_CR2_OIS2 BIT(TIMER_CR2_OIS2_BIT) +#define TIMER_CR2_OIS1N BIT(TIMER_CR2_OIS1N_BIT) +#define TIMER_CR2_OIS1 BIT(TIMER_CR2_OIS1_BIT) +#define TIMER_CR2_TI1S BIT(TIMER_CR2_TI1S_BIT) +#define TIMER_CR2_MMS (0x7 << 4) +#define TIMER_CR2_MMS_RESET (0x0 << 4) +#define TIMER_CR2_MMS_ENABLE (0x1 << 4) +#define TIMER_CR2_MMS_UPDATE (0x2 << 4) +#define TIMER_CR2_MMS_COMPARE_PULSE (0x3 << 4) +#define TIMER_CR2_MMS_COMPARE_OC1REF (0x4 << 4) +#define TIMER_CR2_MMS_COMPARE_OC2REF (0x5 << 4) +#define TIMER_CR2_MMS_COMPARE_OC3REF (0x6 << 4) +#define TIMER_CR2_MMS_COMPARE_OC4REF (0x7 << 4) +#define TIMER_CR2_CCDS BIT(TIMER_CR2_CCDS_BIT) +#define TIMER_CR2_CCUS BIT(TIMER_CR2_CCUS_BIT) +#define TIMER_CR2_CCPC BIT(TIMER_CR2_CCPC_BIT) + +/* Slave mode control register (SMCR) */ + +#define TIMER_SMCR_ETP_BIT 15 +#define TIMER_SMCR_ECE_BIT 14 +#define TIMER_SMCR_MSM_BIT 7 + +#define TIMER_SMCR_ETP BIT(TIMER_SMCR_ETP_BIT) +#define TIMER_SMCR_ECE BIT(TIMER_SMCR_ECE_BIT) +#define TIMER_SMCR_ETPS (0x3 << 12) +#define TIMER_SMCR_ETPS_OFF (0x0 << 12) +#define TIMER_SMCR_ETPS_DIV2 (0x1 << 12) +#define TIMER_SMCR_ETPS_DIV4 (0x2 << 12) +#define TIMER_SMCR_ETPS_DIV8 (0x3 << 12) +#define TIMER_SMCR_ETF (0xF << 12) +#define TIMER_SMCR_MSM BIT(TIMER_SMCR_MSM_BIT) +#define TIMER_SMCR_TS (0x3 << 4) +#define TIMER_SMCR_TS_ITR0 (0x0 << 4) +#define TIMER_SMCR_TS_ITR1 (0x1 << 4) +#define TIMER_SMCR_TS_ITR2 (0x2 << 4) +#define TIMER_SMCR_TS_ITR3 (0x3 << 4) +#define TIMER_SMCR_TS_TI1F_ED (0x4 << 4) +#define TIMER_SMCR_TS_TI1FP1 (0x5 << 4) +#define TIMER_SMCR_TS_TI2FP2 (0x6 << 4) +#define TIMER_SMCR_TS_ETRF (0x7 << 4) +#define TIMER_SMCR_SMS 0x3 +#define TIMER_SMCR_SMS_DISABLED 0x0 +#define TIMER_SMCR_SMS_ENCODER1 0x1 +#define TIMER_SMCR_SMS_ENCODER2 0x2 +#define TIMER_SMCR_SMS_ENCODER3 0x3 +#define TIMER_SMCR_SMS_RESET 0x4 +#define TIMER_SMCR_SMS_GATED 0x5 +#define TIMER_SMCR_SMS_TRIGGER 0x6 +#define TIMER_SMCR_SMS_EXTERNAL 0x7 + +/* DMA/Interrupt enable register (DIER) */ + +#define TIMER_DIER_TDE_BIT 14 +#define TIMER_DIER_CC4DE_BIT 12 +#define TIMER_DIER_CC3DE_BIT 11 +#define TIMER_DIER_CC2DE_BIT 10 +#define TIMER_DIER_CC1DE_BIT 9 +#define TIMER_DIER_UDE_BIT 8 +#define TIMER_DIER_TIE_BIT 6 +#define TIMER_DIER_CC4IE_BIT 4 +#define TIMER_DIER_CC3IE_BIT 3 +#define TIMER_DIER_CC2IE_BIT 2 +#define TIMER_DIER_CC1IE_BIT 1 +#define TIMER_DIER_UIE_BIT 0 + +#define TIMER_DIER_TDE BIT(TIMER_DIER_TDE_BIT) +#define TIMER_DIER_CC4DE BIT(TIMER_DIER_CC4DE_BIT) +#define TIMER_DIER_CC3DE BIT(TIMER_DIER_CC3DE_BIT) +#define TIMER_DIER_CC2DE BIT(TIMER_DIER_CC2DE_BIT) +#define TIMER_DIER_CC1DE BIT(TIMER_DIER_CC1DE_BIT) +#define TIMER_DIER_UDE BIT(TIMER_DIER_UDE_BIT) +#define TIMER_DIER_TIE BIT(TIMER_DIER_TIE_BIT) +#define TIMER_DIER_CC4IE BIT(TIMER_DIER_CC4IE_BIT) +#define TIMER_DIER_CC3IE BIT(TIMER_DIER_CC3IE_BIT) +#define TIMER_DIER_CC2IE BIT(TIMER_DIER_CC2IE_BIT) +#define TIMER_DIER_CC1IE BIT(TIMER_DIER_CC1IE_BIT) +#define TIMER_DIER_UIE BIT(TIMER_DIER_UIE_BIT) + +/* Status register (SR) */ + +#define TIMER_SR_CC4OF_BIT 12 +#define TIMER_SR_CC3OF_BIT 11 +#define TIMER_SR_CC2OF_BIT 10 +#define TIMER_SR_CC1OF_BIT 9 +#define TIMER_SR_BIF_BIT 7 +#define TIMER_SR_TIF_BIT 6 +#define TIMER_SR_COMIF_BIT 5 +#define TIMER_SR_CC4IF_BIT 4 +#define TIMER_SR_CC3IF_BIT 3 +#define TIMER_SR_CC2IF_BIT 2 +#define TIMER_SR_CC1IF_BIT 1 +#define TIMER_SR_UIF_BIT 0 + +#define TIMER_SR_CC4OF BIT(TIMER_SR_CC4OF_BIT) +#define TIMER_SR_CC3OF BIT(TIMER_SR_CC3OF_BIT) +#define TIMER_SR_CC2OF BIT(TIMER_SR_CC2OF_BIT) +#define TIMER_SR_CC1OF BIT(TIMER_SR_CC1OF_BIT) +#define TIMER_SR_BIF BIT(TIMER_SR_BIF_BIT) +#define TIMER_SR_TIF BIT(TIMER_SR_TIF_BIT) +#define TIMER_SR_COMIF BIT(TIMER_SR_COMIF_BIT) +#define TIMER_SR_CC4IF BIT(TIMER_SR_CC4IF_BIT) +#define TIMER_SR_CC3IF BIT(TIMER_SR_CC3IF_BIT) +#define TIMER_SR_CC2IF BIT(TIMER_SR_CC2IF_BIT) +#define TIMER_SR_CC1IF BIT(TIMER_SR_CC1IF_BIT) +#define TIMER_SR_UIF BIT(TIMER_SR_UIF_BIT) + +/* Event generation register (EGR) */ + +#define TIMER_EGR_TG_BIT 6 +#define TIMER_EGR_CC4G_BIT 4 +#define TIMER_EGR_CC3G_BIT 3 +#define TIMER_EGR_CC2G_BIT 2 +#define TIMER_EGR_CC1G_BIT 1 +#define TIMER_EGR_UG_BIT 0 + +#define TIMER_EGR_TG BIT(TIMER_EGR_TG_BIT) +#define TIMER_EGR_CC4G BIT(TIMER_EGR_CC4G_BIT) +#define TIMER_EGR_CC3G BIT(TIMER_EGR_CC3G_BIT) +#define TIMER_EGR_CC2G BIT(TIMER_EGR_CC2G_BIT) +#define TIMER_EGR_CC1G BIT(TIMER_EGR_CC1G_BIT) +#define TIMER_EGR_UG BIT(TIMER_EGR_UG_BIT) + +/* Capture/compare mode registers, common values */ + +#define TIMER_CCMR_CCS_OUTPUT 0x0 +#define TIMER_CCMR_CCS_INPUT_TI1 0x1 +#define TIMER_CCMR_CCS_INPUT_TI2 0x2 +#define TIMER_CCMR_CCS_INPUT_TRC 0x3 + +/* Capture/compare mode register 1 (CCMR1) */ + +#define TIMER_CCMR1_OC2CE_BIT 15 +#define TIMER_CCMR1_OC2PE_BIT 11 +#define TIMER_CCMR1_OC2FE_BIT 10 +#define TIMER_CCMR1_OC1CE_BIT 7 +#define TIMER_CCMR1_OC1PE_BIT 3 +#define TIMER_CCMR1_OC1FE_BIT 2 + +#define TIMER_CCMR1_OC2CE BIT(TIMER_CCMR1_OC2CE_BIT) +#define TIMER_CCMR1_OC2M (0x3 << 12) +#define TIMER_CCMR1_IC2F (0xF << 12) +#define TIMER_CCMR1_OC2PE BIT(TIMER_CCMR1_OC2PE_BIT) +#define TIMER_CCMR1_OC2FE BIT(TIMER_CCMR1_OC2FE_BIT) +#define TIMER_CCMR1_IC2PSC (0x3 << 10) +#define TIMER_CCMR1_CC2S (0x3 << 8) +#define TIMER_CCMR1_CC2S_OUTPUT (TIMER_CCMR_CCS_OUTPUT << 8) +#define TIMER_CCMR1_CC2S_INPUT_TI1 (TIMER_CCMR_CCS_INPUT_TI1 << 8) +#define TIMER_CCMR1_CC2S_INPUT_TI2 (TIMER_CCMR_CCS_INPUT_TI2 << 8) +#define TIMER_CCMR1_CC2S_INPUT_TRC (TIMER_CCMR_CCS_INPUT_TRC << 8) +#define TIMER_CCMR1_OC1CE BIT(TIMER_CCMR1_OC1CE_BIT) +#define TIMER_CCMR1_OC1M (0x3 << 4) +#define TIMER_CCMR1_IC1F (0xF << 4) +#define TIMER_CCMR1_OC1PE BIT(TIMER_CCMR1_OC1PE_BIT) +#define TIMER_CCMR1_OC1FE BIT(TIMER_CCMR1_OC1FE_BIT) +#define TIMER_CCMR1_IC1PSC (0x3 << 2) +#define TIMER_CCMR1_CC1S 0x3 +#define TIMER_CCMR1_CC1S_OUTPUT TIMER_CCMR_CCS_OUTPUT +#define TIMER_CCMR1_CC1S_INPUT_TI1 TIMER_CCMR_CCS_INPUT_TI1 +#define TIMER_CCMR1_CC1S_INPUT_TI2 TIMER_CCMR_CCS_INPUT_TI2 +#define TIMER_CCMR1_CC1S_INPUT_TRC TIMER_CCMR_CCS_INPUT_TRC + +/* Capture/compare mode register 2 (CCMR2) */ + +#define TIMER_CCMR2_OC4CE_BIT 15 +#define TIMER_CCMR2_OC4PE_BIT 11 +#define TIMER_CCMR2_OC4FE_BIT 10 +#define TIMER_CCMR2_OC3CE_BIT 7 +#define TIMER_CCMR2_OC3PE_BIT 3 +#define TIMER_CCMR2_OC3FE_BIT 2 + +#define TIMER_CCMR2_OC4CE BIT(TIMER_CCMR2_OC4CE_BIT) +#define TIMER_CCMR2_OC4M (0x3 << 12) +#define TIMER_CCMR2_IC2F (0xF << 12) +#define TIMER_CCMR2_OC4PE BIT(TIMER_CCMR2_OC4PE_BIT) +#define TIMER_CCMR2_OC4FE BIT(TIMER_CCMR2_OC4FE_BIT) +#define TIMER_CCMR2_IC2PSC (0x3 << 10) +#define TIMER_CCMR2_CC4S (0x3 << 8) +#define TIMER_CCMR1_CC4S_OUTPUT (TIMER_CCMR_CCS_OUTPUT << 8) +#define TIMER_CCMR1_CC4S_INPUT_TI1 (TIMER_CCMR_CCS_INPUT_TI1 << 8) +#define TIMER_CCMR1_CC4S_INPUT_TI2 (TIMER_CCMR_CCS_INPUT_TI2 << 8) +#define TIMER_CCMR1_CC4S_INPUT_TRC (TIMER_CCMR_CCS_INPUT_TRC << 8) +#define TIMER_CCMR2_OC3CE BIT(TIMER_CCMR2_OC3CE_BIT) +#define TIMER_CCMR2_OC3M (0x3 << 4) +#define TIMER_CCMR2_IC1F (0xF << 4) +#define TIMER_CCMR2_OC3PE BIT(TIMER_CCMR2_OC3PE_BIT) +#define TIMER_CCMR2_OC3FE BIT(TIMER_CCMR2_OC3FE_BIT) +#define TIMER_CCMR2_IC1PSC (0x3 << 2) +#define TIMER_CCMR2_CC3S 0x3 +#define TIMER_CCMR1_CC3S_OUTPUT TIMER_CCMR_CCS_OUTPUT +#define TIMER_CCMR1_CC3S_INPUT_TI1 TIMER_CCMR_CCS_INPUT_TI1 +#define TIMER_CCMR1_CC3S_INPUT_TI2 TIMER_CCMR_CCS_INPUT_TI2 +#define TIMER_CCMR1_CC3S_INPUT_TRC TIMER_CCMR_CCS_INPUT_TRC + +/* Capture/compare enable register (CCER) */ + +#define TIMER_CCER_CC4P_BIT 13 +#define TIMER_CCER_CC4E_BIT 12 +#define TIMER_CCER_CC3P_BIT 9 +#define TIMER_CCER_CC3E_BIT 8 +#define TIMER_CCER_CC2P_BIT 5 +#define TIMER_CCER_CC2E_BIT 4 +#define TIMER_CCER_CC1P_BIT 1 +#define TIMER_CCER_CC1E_BIT 0 + +#define TIMER_CCER_CC4P BIT(TIMER_CCER_CC4P_BIT) +#define TIMER_CCER_CC4E BIT(TIMER_CCER_CC4E_BIT) +#define TIMER_CCER_CC3P BIT(TIMER_CCER_CC3P_BIT) +#define TIMER_CCER_CC3E BIT(TIMER_CCER_CC3E_BIT) +#define TIMER_CCER_CC2P BIT(TIMER_CCER_CC2P_BIT) +#define TIMER_CCER_CC2E BIT(TIMER_CCER_CC2E_BIT) +#define TIMER_CCER_CC1P BIT(TIMER_CCER_CC1P_BIT) +#define TIMER_CCER_CC1E BIT(TIMER_CCER_CC1E_BIT) + +/* Break and dead-time register (BDTR) */ + +#define TIMER_BDTR_MOE_BIT 15 +#define TIMER_BDTR_AOE_BIT 14 +#define TIMER_BDTR_BKP_BIT 13 +#define TIMER_BDTR_BKE_BIT 12 +#define TIMER_BDTR_OSSR_BIT 11 +#define TIMER_BDTR_OSSI_BIT 10 + +#define TIMER_BDTR_MOE BIT(TIMER_BDTR_MOE_BIT) +#define TIMER_BDTR_AOE BIT(TIMER_BDTR_AOE_BIT) +#define TIMER_BDTR_BKP BIT(TIMER_BDTR_BKP_BIT) +#define TIMER_BDTR_BKE BIT(TIMER_BDTR_BKE_BIT) +#define TIMER_BDTR_OSSR BIT(TIMER_BDTR_OSSR_BIT) +#define TIMER_BDTR_OSSI BIT(TIMER_BDTR_OSSI_BIT) +#define TIMER_BDTR_LOCK (0x3 << 8) +#define TIMER_BDTR_LOCK_OFF (0x0 << 8) +#define TIMER_BDTR_LOCK_LEVEL1 (0x1 << 8) +#define TIMER_BDTR_LOCK_LEVEL2 (0x2 << 8) +#define TIMER_BDTR_LOCK_LEVEL3 (0x3 << 8) +#define TIMER_BDTR_DTG 0xFF + +/* DMA control register (DCR) */ + +#define TIMER_DCR_DBL (0x1F << 8) +#define TIMER_DCR_DBL_1BYTE (0x0 << 8) +#define TIMER_DCR_DBL_2BYTE (0x1 << 8) +#define TIMER_DCR_DBL_3BYTE (0x2 << 8) +#define TIMER_DCR_DBL_4BYTE (0x3 << 8) +#define TIMER_DCR_DBL_5BYTE (0x4 << 8) +#define TIMER_DCR_DBL_6BYTE (0x5 << 8) +#define TIMER_DCR_DBL_7BYTE (0x6 << 8) +#define TIMER_DCR_DBL_8BYTE (0x7 << 8) +#define TIMER_DCR_DBL_9BYTE (0x8 << 8) +#define TIMER_DCR_DBL_10BYTE (0x9 << 8) +#define TIMER_DCR_DBL_11BYTE (0xA << 8) +#define TIMER_DCR_DBL_12BYTE (0xB << 8) +#define TIMER_DCR_DBL_13BYTE (0xC << 8) +#define TIMER_DCR_DBL_14BYTE (0xD << 8) +#define TIMER_DCR_DBL_15BYTE (0xE << 8) +#define TIMER_DCR_DBL_16BYTE (0xF << 8) +#define TIMER_DCR_DBL_17BYTE (0x10 << 8) +#define TIMER_DCR_DBL_18BYTE (0x11 << 8) +#define TIMER_DCR_DBA 0x1F +#define TIMER_DCR_DBA_CR1 0x0 +#define TIMER_DCR_DBA_CR2 0x1 +#define TIMER_DCR_DBA_SMCR 0x2 +#define TIMER_DCR_DBA_DIER 0x3 +#define TIMER_DCR_DBA_SR 0x4 +#define TIMER_DCR_DBA_EGR 0x5 +#define TIMER_DCR_DBA_CCMR1 0x6 +#define TIMER_DCR_DBA_CCMR2 0x7 +#define TIMER_DCR_DBA_CCER 0x8 +#define TIMER_DCR_DBA_CNT 0x9 +#define TIMER_DCR_DBA_PSC 0xA +#define TIMER_DCR_DBA_ARR 0xB +#define TIMER_DCR_DBA_RCR 0xC +#define TIMER_DCR_DBA_CCR1 0xD +#define TIMER_DCR_DBA_CCR2 0xE +#define TIMER_DCR_DBA_CCR3 0xF +#define TIMER_DCR_DBA_CCR4 0x10 +#define TIMER_DCR_DBA_BDTR 0x11 +#define TIMER_DCR_DBA_DCR 0x12 +#define TIMER_DCR_DBA_DMAR 0x13 + +/* + * Convenience routines + */ + +/** + * Used to configure the behavior of a timer channel. Note that not + * all timers can be configured in every mode. + */ +/* TODO TIMER_PWM_CENTER_ALIGNED, TIMER_INPUT_CAPTURE, TIMER_ONE_PULSE */ +typedef enum timer_mode { + TIMER_DISABLED, /**< In this mode, the timer stops counting, + channel interrupts are detached, and no state + changes are output. */ + TIMER_PWM, /**< PWM output mode. This is the default mode for pins + after initialization. */ + /* TIMER_PWM_CENTER_ALIGNED, /\**< Center-aligned PWM output mode. *\/ */ + TIMER_OUTPUT_COMPARE, /**< In this mode, the timer counts from 0 + to its reload value repeatedly; every + time the counter value reaches one of + the channel compare values, the + corresponding interrupt is fired. */ + /* TIMER_INPUT_CAPTURE, /\**< In this mode, the timer can measure the */ + /* pulse lengths of input signals. *\/ */ + /* TIMER_ONE_PULSE /\**< In this mode, the timer can generate a single */ + /* pulse on a GPIO pin for a specified amount of */ + /* time. *\/ */ +} timer_mode; + +/** Timer channel numbers */ +typedef enum timer_channel { + TIMER_CH1 = 1, /**< Channel 1 */ + TIMER_CH2 = 2, /**< Channel 2 */ + TIMER_CH3 = 3, /**< Channel 3 */ + TIMER_CH4 = 4 /**< Channel 4 */ +} timer_channel; + +/* + * Note: Don't require timer_channel arguments! We want to be able to say + * + * for (int channel = 1; channel <= 4; channel++) { + * ... + * } + * + * without the compiler yelling at us. + */ + +void timer_init(timer_dev *dev); +void timer_disable(timer_dev *dev); +void timer_set_mode(timer_dev *dev, uint8 channel, timer_mode mode); +void timer_foreach(void (*fn)(timer_dev*)); + +/** + * @brief Timer interrupt number. + * + * Not all timers support all of these values; see the descriptions + * for each value. + */ +typedef enum timer_interrupt_id { + TIMER_UPDATE_INTERRUPT, /**< Update interrupt, available on all timers. */ + TIMER_CC1_INTERRUPT, /**< Capture/compare 1 interrupt, available + on general and advanced timers only. */ + TIMER_CC2_INTERRUPT, /**< Capture/compare 2 interrupt, general and + advanced timers only. */ + TIMER_CC3_INTERRUPT, /**< Capture/compare 3 interrupt, general and + advanced timers only. */ + TIMER_CC4_INTERRUPT, /**< Capture/compare 4 interrupt, general and + advanced timers only. */ + TIMER_COM_INTERRUPT, /**< COM interrupt, advanced timers only */ + TIMER_TRG_INTERRUPT, /**< Trigger interrupt, general and advanced + timers only */ + TIMER_BREAK_INTERRUPT /**< Break interrupt, advanced timers only. */ +} timer_interrupt_id; + +void timer_attach_interrupt(timer_dev *dev, + uint8 interrupt, + voidFuncPtr handler); +void timer_detach_interrupt(timer_dev *dev, uint8 interrupt); + +/** + * Initialize all timer devices on the chip. + */ +static inline void timer_init_all(void) { + timer_foreach(timer_init); +} + +/** + * Disables all timers on the device. + */ +static inline void timer_disable_all(void) { + timer_foreach(timer_disable); +} + +/** + * @brief Stop a timer's counter from changing. + * + * Does not affect the timer's mode or other settings. + * + * @param dev Device whose counter to pause. + */ +static inline void timer_pause(timer_dev *dev) { + *bb_perip(&(dev->regs).bas->CR1, TIMER_CR1_CEN_BIT) = 0; +} + +/** + * @brief Start a timer's counter. + * + * Does not affect the timer's mode or other settings. + * + * @param dev Device whose counter to resume + */ +static inline void timer_resume(timer_dev *dev) { + *bb_perip(&(dev->regs).bas->CR1, TIMER_CR1_CEN_BIT) = 1; +} + +/** + * @brief Returns the timer's counter value. + * + * This value is likely to be inaccurate if the counter is running + * with a low prescaler. + * + * @param dev Timer whose counter to return + */ +static inline uint16 timer_get_count(timer_dev *dev) { + return (uint16)(dev->regs).bas->CNT; +} + +/** + * @brief Sets the counter value for the given timer. + * @param timer_num Timer whose counter to set + * @param value New counter value + */ +static inline void timer_set_count(timer_dev *dev, uint16 value) { + (dev->regs).bas->CNT = value; +} + +/** + * @brief Returns the given timer's prescaler. + * + * Note that if the timer's prescaler is set (e.g. via + * timer_set_prescaler() or accessing a TIMx_PSC register), the value + * returned by this function will reflect the new setting, but the + * timer's counter will only reflect the new prescaler at the next + * update event. + * + * @param dev Timer whose prescaler to return + * @see timer_generate_update() + */ +static inline uint16 timer_get_prescaler(timer_dev *dev) { + return (uint16)(dev->regs).bas->PSC; +} + +/** + * @brief Set a timer's prescale value. + * + * The new value will not take effect until the next update event. + * + * @param dev Timer whose prescaler to set + * @param psc New prescaler value + * @see timer_generate_update() + */ +static inline void timer_set_prescaler(timer_dev *dev, uint16 psc) { + (dev->regs).bas->PSC = psc; +} + +/** + * @brief Returns a timer's reload value. + * @param dev Timer whose reload value to return + */ +static inline uint16 timer_get_reload(timer_dev *dev) { + return (uint16)(dev->regs).bas->ARR; +} + +/** + * @brief Set a timer's reload value. + * @param dev Timer whose reload value to set + * @param arr New reload value to use. Takes effect at next update event. + * @see timer_generate_update() + */ +static inline void timer_set_reload(timer_dev *dev, uint16 arr) { + (dev->regs).bas->ARR = arr; +} + +/** + * @brief Get the compare value for the given timer channel. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel whose compare value to get. + */ +static inline uint16 timer_get_compare(timer_dev *dev, uint8 channel) { + __io uint32 *ccr = &(dev->regs).gen->CCR1 + (channel - 1); + return *ccr; +} + +/** + * @brief Set the compare value for the given timer channel. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel whose compare value to set. + * @param value New compare value. + */ +static inline void timer_set_compare(timer_dev *dev, + uint8 channel, + uint16 value) { + __io uint32 *ccr = &(dev->regs).gen->CCR1 + (channel - 1); + *ccr = value; +} + +/** + * @brief Generate an update event for the given timer. + * + * Normally, this will cause the prescaler and auto-reload values in + * the PSC and ARR registers to take immediate effect. However, this + * function will do nothing if the UDIS bit is set in the timer's CR1 + * register (UDIS is cleared by default). + * + * @param dev Timer device to generate an update for. + */ +static inline void timer_generate_update(timer_dev *dev) { + *bb_perip(&(dev->regs).bas->EGR, TIMER_EGR_UG_BIT) = 1; +} + +/** + * @brief Enable a timer's trigger DMA request + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL + */ +static inline void timer_trigger_dma_enable_request(timer_dev *dev) { + *bb_perip(&(dev->regs).gen->DIER, TIMER_DIER_TDE_BIT) = 1; +} + +/** + * @brief Disable a timer's trigger DMA request + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL + */ +static inline void timer_trigger_dma_disable_request(timer_dev *dev) { + *bb_perip(&(dev->regs).gen->DIER, TIMER_DIER_TDE_BIT) = 0; +} + +/** + * @brief Enable a timer channel's DMA request. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL + * @param channel Channel whose DMA request to enable. + */ +static inline void timer_dma_enable_request(timer_dev *dev, uint8 channel) { + *bb_perip(&(dev->regs).gen->DIER, channel + 8) = 1; +} + +/** + * @brief Disable a timer channel's DMA request. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel whose DMA request to disable. + */ +static inline void timer_dma_disable_request(timer_dev *dev, uint8 channel) { + *bb_perip(&(dev->regs).gen->DIER, channel + 8) = 0; +} + +/** + * @brief Enable a timer interrupt. + * @param dev Timer device. + * @param interrupt Interrupt number to enable; this may be any + * timer_interrupt_id value appropriate for the timer. + * @see timer_interrupt_id + * @see timer_channel + */ +static inline void timer_enable_interrupt(timer_dev *dev, uint8 interrupt) { + *bb_perip(&(dev->regs).adv->DIER, interrupt) = 1; +} + +/** + * @brief Disable a timer interrupt. + * @param dev Timer device. + * @param interrupt Interrupt number to disable; this may be any + * timer_interrupt_id value appropriate for the timer. + * @see timer_interrupt_id + * @see timer_channel + */ +static inline void timer_disable_interrupt(timer_dev *dev, uint8 interrupt) { + *bb_perip(&(dev->regs).adv->DIER, interrupt) = 0; +} + +/** + * @brief Enable a timer channel's capture/compare signal. + * + * If the channel is configured as output, the corresponding output + * compare signal will be output on the corresponding output pin. If + * the channel is configured as input, enables capture of the counter + * value into the input capture/compare register. + * + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel to enable, from 1 to 4. + */ +static inline void timer_cc_enable(timer_dev *dev, uint8 channel) { + *bb_perip(&(dev->regs).gen->CCER, 4 * (channel - 1)) = 1; +} + +/** + * @brief Disable a timer channel's output compare or input capture signal. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel to disable, from 1 to 4. + * @see timer_cc_enable() + */ +static inline void timer_cc_disable(timer_dev *dev, uint8 channel) { + *bb_perip(&(dev->regs).gen->CCER, 4 * (channel - 1)) = 0; +} + +/** + * @brief Get a channel's capture/compare output polarity + * @brief dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @brief channel Channel whose capture/compare output polarity to get. + * @return Polarity, either 0 or 1. + * @see timer_cc_set_polarity() + */ +static inline uint8 timer_cc_get_polarity(timer_dev *dev, uint8 channel) { + return *bb_perip(&(dev->regs).gen->CCER, 4 * (channel - 1) + 1); +} + +/** + * @brief Set a timer channel's capture/compare output polarity. + * + * If the timer channel is configured as output: polarity == 0 means + * the output channel will be active high; polarity == 1 means active + * low. + * + * If the timer channel is configured as input: polarity == 0 means + * capture is done on the rising edge of ICn; when used as an external + * trigger, ICn is non-inverted. polarity == 1 means capture is done + * on the falling edge of ICn; when used as an external trigger, ICn + * is inverted. + * + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel whose capture/compare output polarity to set. + * @param pol New polarity, 0 or 1. + */ +static inline void timer_cc_set_polarity(timer_dev *dev, + uint8 channel, + uint8 pol) { + *bb_perip(&(dev->regs).gen->CCER, 4 * (channel - 1) + 1) = pol; +} + +/** + * @brief Get a timer's DMA burst length. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @return Number of bytes to be transferred per DMA request, from 1 to 18. + */ +static inline uint8 timer_get_dma_burst_length(timer_dev *dev) { + uint32 dbl = ((dev->regs).gen->DCR & TIMER_DCR_DBL) >> 8; + return dbl + 1; /* 0 means 1 byte, etc. */ +} + +/** + * @brief Set a timer's DMA burst length. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param length DMA burst length; i.e., number of bytes to transfer + * per DMA request, from 1 to 18. + */ +static inline void timer_set_dma_burst_length(timer_dev *dev, uint8 length) { + uint32 tmp = (dev->regs).gen->DCR; + tmp &= ~TIMER_DCR_DBL; + tmp |= (length << 8) - 1; + (dev->regs).gen->DCR = tmp; +} + +/** + * @brief Timer DMA base address. + * + * Defines the base address for DMA transfers. + */ +typedef enum timer_dma_base_address { + TIMER_DMA_BASE_CR1 = TIMER_DCR_DBA_CR1, /**< Base is control register 1 */ + TIMER_DMA_BASE_CR2 = TIMER_DCR_DBA_CR2, /**< Base is control register 2 */ + TIMER_DMA_BASE_SMCR = TIMER_DCR_DBA_SMCR, /**< Base is slave mode + control register */ + TIMER_DMA_BASE_DIER = TIMER_DCR_DBA_DIER, /**< Base is DMA interrupt enable + register */ + TIMER_DMA_BASE_SR = TIMER_DCR_DBA_SR, /**< Base is status register */ + TIMER_DMA_BASE_EGR = TIMER_DCR_DBA_EGR, /**< Base is event generation + register */ + TIMER_DMA_BASE_CCMR1 = TIMER_DCR_DBA_CCMR1, /**< Base is capture/compare + mode register 1 */ + TIMER_DMA_BASE_CCMR2 = TIMER_DCR_DBA_CCMR2, /**< Base is capture/compare + mode register 2 */ + TIMER_DMA_BASE_CCER = TIMER_DCR_DBA_CCER, /**< Base is capture/compare + enable register */ + TIMER_DMA_BASE_CNT = TIMER_DCR_DBA_CNT, /**< Base is counter */ + TIMER_DMA_BASE_PSC = TIMER_DCR_DBA_PSC, /**< Base is prescaler */ + TIMER_DMA_BASE_ARR = TIMER_DCR_DBA_ARR, /**< Base is auto-reload + register */ + TIMER_DMA_BASE_RCR = TIMER_DCR_DBA_RCR, /**< Base is repetition + counter register */ + TIMER_DMA_BASE_CCR1 = TIMER_DCR_DBA_CCR1, /**< Base is capture/compare + register 1 */ + TIMER_DMA_BASE_CCR2 = TIMER_DCR_DBA_CCR2, /**< Base is capture/compare + register 2 */ + TIMER_DMA_BASE_CCR3 = TIMER_DCR_DBA_CCR3, /**< Base is capture/compare + register 3 */ + TIMER_DMA_BASE_CCR4 = TIMER_DCR_DBA_CCR4, /**< Base is capture/compare + register 4 */ + TIMER_DMA_BASE_BDTR = TIMER_DCR_DBA_BDTR, /**< Base is break and + dead-time register */ + TIMER_DMA_BASE_DCR = TIMER_DCR_DBA_DCR, /**< Base is DMA control + register */ + TIMER_DMA_BASE_DMAR = TIMER_DCR_DBA_DMAR /**< Base is DMA address for + full transfer */ +} timer_dma_base_address; + +/** + * @brief Get the timer's DMA base address. + * + * Some restrictions apply; see ST RM0008. + * + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @return DMA base address + */ +static inline timer_dma_base_address +timer_get_dma_base_address(timer_dev *dev) { + uint32 dcr = (dev->regs).gen->DCR; + return (timer_dma_base_address)(dcr & TIMER_DCR_DBA); +} + +/** + * @brief Set the timer's DMA base address. + * + * Some restrictions apply; see ST RM0008. + * + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param dma_base DMA base address. + */ +static inline void +timer_set_dma_base_address(timer_dev *dev, timer_dma_base_address dma_base) { + uint32 tmp = (dev->regs).gen->DCR; + tmp &= ~TIMER_DCR_DBA; + tmp |= dma_base; + (dev->regs).gen->DCR = tmp; +} + +/** + * Timer output compare modes. + */ +typedef enum timer_oc_mode { + TIMER_OC_MODE_FROZEN = 0 << 4, /**< Frozen: comparison between output + compare register and counter has no + effect on the outputs. */ + TIMER_OC_MODE_ACTIVE_ON_MATCH = 1 << 4, /**< OCxREF signal is forced + high when the count matches + the channel capture/compare + register. */ + TIMER_OC_MODE_INACTIVE_ON_MATCH = 2 << 4, /**< OCxREF signal is forced + low when the counter matches + the channel capture/compare + register. */ + TIMER_OC_MODE_TOGGLE = 3 << 4, /**< OCxREF toggles when counter + matches the cannel capture/compare + register. */ + TIMER_OC_MODE_FORCE_INACTIVE = 4 << 4, /**< OCxREF is forced low. */ + TIMER_OC_MODE_FORCE_ACTIVE = 5 << 4, /**< OCxREF is forced high. */ + TIMER_OC_MODE_PWM_1 = 6 << 4, /**< PWM mode 1. In upcounting, channel is + active as long as count is less than + channel capture/compare register, else + inactive. In downcounting, channel is + inactive as long as count exceeds + capture/compare register, else + active. */ + TIMER_OC_MODE_PWM_2 = 7 << 4 /**< PWM mode 2. In upcounting, channel is + inactive as long as count is less than + capture/compare register, else active. + In downcounting, channel is active as + long as count exceeds capture/compare + register, else inactive. */ +} timer_oc_mode; + +/** + * Timer output compare mode flags. + * @see timer_oc_set_mode() + */ +typedef enum timer_oc_mode_flags { + TIMER_OC_CE = BIT(7), /**< Output compare clear enable. */ + TIMER_OC_PE = BIT(3), /**< Output compare preload enable. */ + TIMER_OC_FE = BIT(2) /**< Output compare fast enable. */ +} timer_oc_mode_flags; + +/** + * @brief Configure a channel's output compare mode. + * + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel to configure in output compare mode. + * @param flags OR of timer_oc_mode_flags. + * @see timer_oc_mode + * @see timer_oc_mode_flags + */ +static inline void timer_oc_set_mode(timer_dev *dev, + uint8 channel, + timer_oc_mode mode, + uint8 flags) { + uint8 bit0 = channel & 1; + uint8 bit1 = (channel >> 1) & 1; + /* channel == 1,2 -> CCMR1; channel == 3,4 -> CCMR2 */ + __io uint32 *ccmr = &(dev->regs).gen->CCMR1 + bit1; + /* channel == 1,3 -> shift = 0, channel == 2,4 -> shift = 8 */ + uint8 shift = 8 * (1 - bit0); + + uint32 tmp = *ccmr; + tmp &= ~(0xFF << shift); + tmp |= (mode | flags | TIMER_CCMR_CCS_OUTPUT) << shift; + *ccmr = tmp; +} + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/libmaple/timers.c b/libmaple/timers.c deleted file mode 100644 index c561d39..0000000 --- a/libmaple/timers.c +++ /dev/null @@ -1,526 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief General timer routines - */ - -/* TODO: actually support timer5 and timer8 */ - -#include "libmaple.h" -#include "rcc.h" -#include "nvic.h" -#include "timers.h" - -/* Timer descriptor table */ -struct timer_dev timer_dev_table[] = { - [TIMER1] = { - .base = (timer_port*)TIMER1_BASE, - .rcc_dev_num = RCC_TIMER1, - .nvic_dev_num = NVIC_TIMER1 - }, - [TIMER2] = { - .base = (timer_port*)TIMER2_BASE, - .rcc_dev_num = RCC_TIMER2, - .nvic_dev_num = NVIC_TIMER2 - }, - [TIMER3] = { - .base = (timer_port*)TIMER3_BASE, - .rcc_dev_num = RCC_TIMER3, - .nvic_dev_num = NVIC_TIMER3 - }, - [TIMER4] = { - .base = (timer_port*)TIMER4_BASE, - .rcc_dev_num = RCC_TIMER4, - .nvic_dev_num = NVIC_TIMER4 - }, -#ifdef STM32_HIGH_DENSITY - /* High density devices only (eg, Maple Native) */ - [TIMER5] = { - .base = (timer_port*)TIMER5_BASE, - .rcc_dev_num = RCC_TIMER5, - .nvic_dev_num = NVIC_TIMER5 - }, - [TIMER8] = { - .base = (timer_port*)TIMER8_BASE, - .rcc_dev_num = RCC_TIMER8, - .nvic_dev_num = NVIC_TIMER8 - }, -#endif -}; - -/* This function should probably be rewriten to take (timer_num, mode) - * and have prescaler set elsewhere. The mode can be passed through to - * set_mode at the end */ -void timer_init(timer_dev_num timer_num, uint16 prescale) { - /* TODO: doesn't catch 6+7 */ - - timer_port *timer = timer_dev_table[timer_num].base; - uint8 is_advanced = 0; - - if (timer_num == TIMER1) { - is_advanced = 1; - } -#ifdef STM32_HIGH_DENSITY - if (timer_num == TIMER8) { - is_advanced = 1; - } -#endif - - rcc_clk_enable(timer_dev_table[timer_num].rcc_dev_num); - - timer->CR1 = ARPE; // No clock division - // Do not buffer auto-reload preload - // Edge aligned - // Upcounter - // Do not stop counter at update event - // Update events enabled (etc, see bits [1:2]) - // Counter disabled for now - - timer->PSC = prescale; // Prescaling by prescale (duh) - timer->ARR = 0xFFFF; // Max reload cont - - /* initialize all the channels to 50% duty cycle, - * TODO: none of them actually get output unless the gpio pin - * is set, this will probably consume a bit more power but - * we'll worry about that later. */ - timer->CCR1 = 0x8FFF; // PWM start value - timer->CCMR1 |= 0x68; // PWM mode 1, enable preload register. - - timer->CCR2 = 0x8FFF; // PWM start value - timer->CCMR1 |= (0x68 << 8);// PWM mode 1, enable preload register. - - timer->CCR3 = 0x8FFF; // PWM start value - timer->CCMR2 |= 0x68; // PWM mode 1, enable preload register. - - timer->CCR4 = 0x8FFF; // PWM start value - timer->CCMR2 |= (0x68 << 8);// PWM mode 1, enable preload register. - - /* Advanced timer? */ - if (is_advanced) { - timer->BDTR = 0x8000; // moe enable - } - - timer->SR = 0; // clear it - timer->DIER = 0; // disable update interrupt - timer->EGR = 1; // Initialize update event and shadow registers - timer->CR1 |= 1; // Enable timer -} - -/* Stops the counter; the mode and settings are not modified */ -void timer_pause(timer_dev_num timer_num) { - timer_port *timer = timer_dev_table[timer_num].base; - - timer->CR1 &= ~(0x0001); // CEN -} - -/* Starts the counter; the mode and settings are not modified */ -void timer_resume(timer_dev_num timer_num) { - timer_port *timer = timer_dev_table[timer_num].base; - - timer->CR1 |= 0x0001; // CEN -} - -/* Returns the current timer counter value. Probably very inaccurate - * if the counter is running with a low prescaler. */ -uint16 timer_get_count(timer_dev_num timer_num) { - timer_port *timer = timer_dev_table[timer_num].base; - - return timer->CNT; -} - -/* This function sets the counter value via register for the specified - * timer. Can't think of specific usecases except for resetting to - * zero but it's easy to implement and allows for "creative" - * programming */ -void timer_set_count(timer_dev_num timer_num, uint16 value) { - timer_port *timer = timer_dev_table[timer_num].base; - - timer->CNT = value; -} - -/* Get the prescaler buffer value (remember, the actual prescaler - * doesn't get set until an update event). */ -uint16 timer_get_prescaler(timer_dev_num timer_num) { - timer_port *timer = timer_dev_table[timer_num].base; - return timer->PSC; -} - -/* Sets the prescaler */ -void timer_set_prescaler(timer_dev_num timer_num, uint16 prescale) { - timer_port *timer = timer_dev_table[timer_num].base; - - timer->PSC = prescale; -} - -/* Get the reload value for the entire timer. */ -uint16 timer_get_reload(timer_dev_num timer_num) { - timer_port *timer = timer_dev_table[timer_num].base; - return timer->ARR; -} - -/* This sets the "reload" or "overflow" value for the entire timer. We - * should probably settle on either "reload" or "overflow" to prevent - * confusion? */ -void timer_set_reload(timer_dev_num timer_num, uint16 max_reload) { - timer_port *timer = timer_dev_table[timer_num].base; - - timer->ARR = max_reload; -} - -/* This quickly disables all 4 timers, presumably as part of a system shutdown - * or similar to prevent interrupts and PWM output without 16 seperate function - * calls to timer_set_mode */ -void timer_disable_all(void) { - timer_port *timer; -#ifdef STM32_HIGH_DENSITY - timer_port *timers[6] = { (timer_port*)TIMER1_BASE, - (timer_port*)TIMER2_BASE, - (timer_port*)TIMER3_BASE, - (timer_port*)TIMER4_BASE, - (timer_port*)TIMER5_BASE, - (timer_port*)TIMER8_BASE, - }; - uint8 i; - for (i = 0; i < 6; i++) { - timer = timers[i]; - timer->CR1 = 0; - timer->CCER = 0; - } -#else - timer_port *timers[4] = { (timer_port*)TIMER1_BASE, - (timer_port*)TIMER2_BASE, - (timer_port*)TIMER3_BASE, - (timer_port*)TIMER4_BASE, - }; - uint8 i; - for (i = 0; i < 4; i++) { - timer = timers[i]; - timer->CR1 = 0; - timer->CCER = 0; - } -#endif -} - -/* Sets the mode of individual timer channels, including a DISABLE mode */ -void timer_set_mode(timer_dev_num timer_num, uint8 channel, TimerMode mode) { - timer_port *timer = timer_dev_table[timer_num].base; - ASSERT(channel >= 1); - - switch(mode) { - case TIMER_DISABLED: - /* Disable the channel - * Disable any interrupt - * Clear interrupt SR? (TODO) */ - timer->DIER &= ~(1 << channel); // 1-indexed compare nums - timer_detach_interrupt(timer_num, channel); - timer->CCER &= ~(1 << (4*(channel - 1))); // 0-indexed - break; - case TIMER_PWM: - /* Set CCMR mode - * Keep existing reload value - * Disable any interrupt - * Clear interrupt SR? (TODO) - * Enable channel */ - timer->DIER &= ~(1 << channel); // 1-indexed compare nums - switch (channel) { - case 1: - timer->CCMR1 &= ~(0xFF); - timer->CCMR1 |= 0x68; // PWM mode 1, enable preload register. - break; - case 2: - timer->CCMR1 &= ~(0xFF00); - timer->CCMR1 |= (0x68 << 8);// PWM mode 1, enable preload register. - break; - case 3: - timer->CCMR2 &= ~(0xFF); - timer->CCMR2 |= 0x68; // PWM mode 1, enable preload register. - break; - case 4: - timer->CCMR2 &= ~(0xFF00); - timer->CCMR2 |= (0x68 << 8);// PWM mode 1, enable preload register. - break; - default: - ASSERT(0); - } - timer->CCER |= (1 << (4*(channel - 1))); // Enable - break; - case TIMER_OUTPUTCOMPARE: - /* Set CCMR mode - * Keep existing reload value - * Don't modify interrupt (needs to be attached to enable) - * Clear interrupt SR? (TODO) - * Enable channel */ - switch (channel) { - case 1: - timer->CCMR1 &= ~(0xFF); - timer->CCMR1 |= 0x0010; // PWM mode 1, enable preload register. - break; - case 2: - timer->CCMR1 &= ~(0xFF00); - timer->CCMR1 |= 0x1000; // PWM mode 1, enable preload register. - break; - case 3: - timer->CCMR2 &= ~(0xFF); - timer->CCMR2 |= 0x0010; // PWM mode 1, enable preload register. - break; - case 4: - timer->CCMR2 &= ~(0xFF00); - timer->CCMR2 |= 0x1000; // PWM mode 1, enable preload register. - break; - default: - ASSERT(0); - } - timer->CCER |= (1 << (4*(channel - 1))); // Enable - break; - default: - ASSERT(0); - } -} - -uint16 timer_get_compare_value(timer_dev_num timer_num, uint8 channel_num) { - /* faster: just read TIMERx_CHy_CCR (see timers.h) */ - ASSERT(channel_num > 0 && channel_num <= 4); - timer_port *timer = timer_dev_table[timer_num].base; - switch(channel_num) { - case 1: - return timer->CCR1; - case 2: - return timer->CCR2; - case 3: - return timer->CCR3; - case 4: - return timer->CCR4; - default: /* in case ASSERT is disabled */ - return 0; - } -} - -/* This sets the compare value (aka the trigger) for a given timer - * channel */ -void timer_set_compare_value(timer_dev_num timer_num, - uint8 channel_num, - uint16 value) { - ASSERT(channel_num > 0 && channel_num <= 4); - - /* The faster version of this function is the inline - timer_pwm_write_ccr */ - timer_port *timer = timer_dev_table[timer_num].base; - - switch(channel_num) { - case 1: - timer->CCR1 = value; - break; - case 2: - timer->CCR2 = value; - break; - case 3: - timer->CCR3 = value; - break; - case 4: - timer->CCR4 = value; - break; - } -} - -/* Stores a pointer to the passed usercode interrupt function and configures - * the actual ISR so that it will actually be called */ -void timer_attach_interrupt(timer_dev_num timer_num, - uint8 compare_num, - voidFuncPtr handler) { - ASSERT(compare_num > 0 && compare_num <= 4); - - timer_port *timer = timer_dev_table[timer_num].base; - - timer_dev_table[timer_num].handlers[compare_num-1] = handler; - timer->DIER |= (1 << compare_num); // 1-indexed compare nums - nvic_irq_enable(timer_dev_table[timer_num].nvic_dev_num); -} - -void timer_detach_interrupt(timer_dev_num timer_num, uint8 compare_num) { - ASSERT(compare_num > 0 && compare_num <= 4); - - timer_port *timer = timer_dev_table[timer_num].base; - - timer_dev_table[timer_num].handlers[compare_num-1] = 0; - timer->DIER &= ~(1 << compare_num); // 1-indexed compare nums -} - -void timer_generate_update(timer_dev_num timer_num) { - /* cause update event by setting UG bit in EGR. updates prescaler - ratio etc. */ - timer_port *timer = timer_dev_table[timer_num].base; - timer->EGR |= 0x1; -} - -/* The following are the actual interrupt handlers; 1 for each timer which must - * determine which actual compare value (aka channel) was triggered. - * - * These ISRs get called when the timer interrupt is enabled, the - * timer is running, and the timer count equals any of the CCR - * registers /or/ has overflowed. - * - * This is a rather long implementation... */ -void __irq_tim1_cc(void) { - timer_port *timer = (timer_port*)TIMER1_BASE; - uint16 sr_buffer; - sr_buffer = timer->SR; - - /* Simply switch/case-ing here doesn't work because multiple - * CC flags may be high. */ - if(sr_buffer & 0x10){ // CC4 flag - timer->SR &= ~(0x10); - if(timer_dev_table[TIMER1].handlers[3]) { - timer_dev_table[TIMER1].handlers[3](); - } - } - if(sr_buffer & 0x8){ // CC3 flag - timer->SR &= ~(0x8); - if(timer_dev_table[TIMER1].handlers[2]) { - timer_dev_table[TIMER1].handlers[2](); - } - } - if(sr_buffer & 0x4){ // CC2 flag - timer->SR &= ~(0x4); - if(timer_dev_table[TIMER1].handlers[1]) { - timer_dev_table[TIMER1].handlers[1](); - } - } - if(sr_buffer & 0x2){ // CC1 flag - timer->SR &= ~(0x2); - if(timer_dev_table[TIMER1].handlers[0]) { - timer_dev_table[TIMER1].handlers[0](); - } - } - if(sr_buffer & 0x1){ // Update flag - timer->SR &= ~(0x1); - //timer->EGR = 1; - } -} -void __irq_tim2(void) { - /* This is a rather long implementation... */ - timer_port *timer = (timer_port*)TIMER2_BASE; - uint16 sr_buffer; - sr_buffer = timer->SR; - - if(sr_buffer & 0x10){ // CC4 flag - timer->SR &= ~(0x10); - if(timer_dev_table[TIMER2].handlers[3]) { - timer_dev_table[TIMER2].handlers[3](); - } - } - if(sr_buffer & 0x8){ // CC3 flag - timer->SR &= ~(0x8); - if(timer_dev_table[TIMER2].handlers[2]) { - timer_dev_table[TIMER2].handlers[2](); - } - } - if(sr_buffer & 0x4){ // CC2 flag - timer->SR &= ~(0x4); - if(timer_dev_table[TIMER2].handlers[1]) { - timer_dev_table[TIMER2].handlers[1](); - } - } - if(sr_buffer & 0x2){ // CC1 flag - timer->SR &= ~(0x2); - if(timer_dev_table[TIMER2].handlers[0]) { - timer_dev_table[TIMER2].handlers[0](); - } - } - if(sr_buffer & 0x1){ // Update flag - timer->SR &= ~(0x1); - //timer->EGR = 1; - } -} -void __irq_tim3(void) { - /* This is a rather long implementation... */ - timer_port *timer = (timer_port*)TIMER3_BASE; - uint16 sr_buffer; - sr_buffer = timer->SR; - - if(sr_buffer & 0x10){ // CC4 flag - timer->SR &= ~(0x10); - if(timer_dev_table[TIMER3].handlers[3]) { - timer_dev_table[TIMER3].handlers[3](); - } - } - if(sr_buffer & 0x8){ // CC3 flag - timer->SR &= ~(0x8); - if(timer_dev_table[TIMER3].handlers[2]) { - timer_dev_table[TIMER3].handlers[2](); - } - } - if(sr_buffer & 0x4){ // CC2 flag - timer->SR &= ~(0x4); - if(timer_dev_table[TIMER3].handlers[1]) { - timer_dev_table[TIMER3].handlers[1](); - } - } - if(sr_buffer & 0x2){ // CC1 flag - timer->SR &= ~(0x2); - if(timer_dev_table[TIMER3].handlers[0]) { - timer_dev_table[TIMER3].handlers[0](); - } - } - if(sr_buffer & 0x1){ // Update flag - timer->SR &= ~(0x1); - //timer->EGR = 1; - } -} - -void __irq_tim4(void) { - /* This is a rather long implementation... */ - timer_port*timer = (timer_port*)TIMER4_BASE; - uint16 sr_buffer; - sr_buffer = timer->SR; - - if(sr_buffer & 0x10){ // CC4 flag - timer->SR &= ~(0x10); - if(timer_dev_table[TIMER4].handlers[3]) { - timer_dev_table[TIMER4].handlers[3](); - } - } - if(sr_buffer & 0x8){ // CC3 flag - timer->SR &= ~(0x8); - if(timer_dev_table[TIMER4].handlers[2]) { - timer_dev_table[TIMER4].handlers[2](); - } - } - if(sr_buffer & 0x4){ // CC2 flag - timer->SR &= ~(0x4); - if(timer_dev_table[TIMER4].handlers[1]) { - timer_dev_table[TIMER4].handlers[1](); - } - } - if(sr_buffer & 0x2){ // CC1 flag - timer->SR &= ~(0x2); - if(timer_dev_table[TIMER4].handlers[0]) { - timer_dev_table[TIMER4].handlers[0](); - } - } - if(sr_buffer & 0x1){ // Update flag - timer->SR &= ~(0x1); - //timer->EGR = 1; - } -} diff --git a/libmaple/timers.h b/libmaple/timers.h deleted file mode 100644 index 1f6afcd..0000000 --- a/libmaple/timers.h +++ /dev/null @@ -1,435 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @file timers.h - * - * @brief Timer prototypes and various definitions - */ - -/* Note to self: - * The timer clock frequencies are automatically fixed by hardware. - * There are two cases: - * 1. if the APB prescaler is 1, the timer clock frequencies are - * set to the same frequency as that of the APB domain to which - * the timers are connected. - * 2. otherwise, they are set to twice (x2) the frequency of the - * APB domain to which the timers are connected. - * See stm32 manual, 77/995 - * - * hence, 72 mhz timers - */ - -/* Maple Timer channels: - * Timer Maple Pin STM32 Pin Type - * TIM1_CH1 D6 PA8 Advanced - * TIM1_CH2 D7 PA9 Advanced - * TIM1_CH3 D8 PA10 Advanced - * - * TIM2_CH1 D2 PA0 - * TIM2_CH2 D3 PA1 - * TIM2_CH3 D1 PA2 - * TIM2_CH4 D0 PA3 - * - * TIM3_CH1 D12 PA6 - * TIM3_CH2 D11 PA7 - * TIM3_CH3 EXT7 PB0 - * TIM3_CH4 EXT8 PB1 - * - * TIM4_CH1 EXT5 PB6 - * TIM4_CH1 EXT9 PB7 - * TIM4_CH1 EXT15 PB8 - * TIM4_CH1 EXT4 PB9 - * - * Not supported: - * TIM1_CH4 USBDM, not available PA11 Advanced - * TIM1_CH1_N EXT12 PB13 - * TIM1_CH2_N EXT13 PB14 - * TIM1_CH3_N EXT14 PB15 - * */ - -/* I don't like the Arduino API for dealing with pin modes. - * How about... - * - * pinMode(digitalPin, PWM); - * pwmWrite(digitalPin) */ - -#ifndef _TIMERS_H_ -#define _TIMERS_H_ - -#ifdef __cplusplus -extern "C"{ -#endif - -typedef volatile uint16* TimerCCR; - -#define TIMER1_BASE 0x40012C00 -#define TIMER2_BASE 0x40000000 -#define TIMER3_BASE 0x40000400 -#define TIMER4_BASE 0x40000800 -#define TIMER5_BASE 0x40000C00 // High-density devices only -#define TIMER6_BASE 0x40001000 // High-density devices only -#define TIMER7_BASE 0x40001400 // High-density devices only -#define TIMER8_BASE 0x40013400 // High-density devices only - -#define ARPE BIT(7) // Auto-reload preload enable -#define NOT_A_TIMER 0 - -#define TIMER_CCR(NUM,CHAN) (TIMER ## NUM ## _CH ## CHAN ## _CRR) - -/* Timers 1-4 are present on the entire STM32 line. */ - -#define TIMER1_CH1_CCR ((TimerCCR)(TIMER1_BASE + 0x34)) -#define TIMER1_CH2_CCR ((TimerCCR)(TIMER1_BASE + 0x38)) -#define TIMER1_CH3_CCR ((TimerCCR)(TIMER1_BASE + 0x3C)) -#define TIMER1_CH4_CCR ((TimerCCR)(TIMER1_BASE + 0x40)) - -#define TIMER2_CH1_CCR ((TimerCCR)(TIMER2_BASE + 0x34)) -#define TIMER2_CH2_CCR ((TimerCCR)(TIMER2_BASE + 0x38)) -#define TIMER2_CH3_CCR ((TimerCCR)(TIMER2_BASE + 0x3C)) -#define TIMER2_CH4_CCR ((TimerCCR)(TIMER2_BASE + 0x40)) - -#define TIMER3_CH1_CCR ((TimerCCR)(TIMER3_BASE + 0x34)) -#define TIMER3_CH2_CCR ((TimerCCR)(TIMER3_BASE + 0x38)) -#define TIMER3_CH3_CCR ((TimerCCR)(TIMER3_BASE + 0x3C)) -#define TIMER3_CH4_CCR ((TimerCCR)(TIMER3_BASE + 0x40)) - -#define TIMER4_CH1_CCR ((TimerCCR)(TIMER4_BASE + 0x34)) -#define TIMER4_CH2_CCR ((TimerCCR)(TIMER4_BASE + 0x38)) -#define TIMER4_CH3_CCR ((TimerCCR)(TIMER4_BASE + 0x3C)) -#define TIMER4_CH4_CCR ((TimerCCR)(TIMER4_BASE + 0x40)) - -/* Timers 5 and 8 are in high-density devices only (such as Maple - Native). Timers 6 and 7 in these devices have no output compare - pins. */ - -#define TIMER5_CH1_CCR ((TimerCCR)(TIMER5_BASE + 0x34)) -#define TIMER5_CH2_CCR ((TimerCCR)(TIMER5_BASE + 0x38)) -#define TIMER5_CH3_CCR ((TimerCCR)(TIMER5_BASE + 0x3C)) -#define TIMER5_CH4_CCR ((TimerCCR)(TIMER5_BASE + 0x40)) - -#define TIMER8_CH1_CCR ((TimerCCR)(TIMER8_BASE + 0x34)) -#define TIMER8_CH2_CCR ((TimerCCR)(TIMER8_BASE + 0x38)) -#define TIMER8_CH3_CCR ((TimerCCR)(TIMER8_BASE + 0x3C)) -#define TIMER8_CH4_CCR ((TimerCCR)(TIMER8_BASE + 0x40)) - -/** - * Used to configure the behavior of a timer. - */ -typedef enum TimerMode { - TIMER_DISABLED, /**< In this mode, the timer stops counting, - interrupts are not called, and no state changes - are output. */ - TIMER_PWM, /**< This is the default mode for pins after - initialization. */ - TIMER_OUTPUTCOMPARE, /**< In this mode, the timer counts from 0 to - its reload value repeatedly; every time - the counter value reaches one of the - channel compare values, the corresponding - interrupt is fired. */ -} TimerMode; - -typedef struct { - /* Fields up to ARR common to general purpose (2,3,4,5), advanced - control (1,8) and basic (6, 7) timers: */ - volatile uint16 CR1; - uint16 RESERVED0; - volatile uint16 CR2; - uint16 RESERVED1; - volatile uint16 SMCR; - uint16 RESERVED2; - volatile uint16 DIER; - uint16 RESERVED3; - volatile uint16 SR; - uint16 RESERVED4; - volatile uint16 EGR; - uint16 RESERVED5; - volatile uint16 CCMR1; - uint16 RESERVED6; - volatile uint16 CCMR2; - uint16 RESERVED7; - volatile uint16 CCER; - uint16 RESERVED8; - volatile uint16 CNT; - uint16 RESERVED9; - volatile uint16 PSC; - uint16 RESERVED10; - volatile uint16 ARR; - uint16 RESERVED11; - /* Basic timers have none of the following: */ - volatile uint16 RCR; /* Advanced control timers only */ - uint16 RESERVED12; /* Advanced control timers only */ - volatile uint16 CCR1; - uint16 RESERVED13; - volatile uint16 CCR2; - uint16 RESERVED14; - volatile uint16 CCR3; - uint16 RESERVED15; - volatile uint16 CCR4; - uint16 RESERVED16; - volatile uint16 BDTR; /* Advanced control timers only */ - uint16 RESERVED17; /* Advanced control timers only */ - volatile uint16 DCR; - uint16 RESERVED18; - volatile uint16 DMAR; - uint16 RESERVED19; -} timer_port; - -/** - * Timer device numbers. See STM32 reference manual, chapters 13-15. - */ -/* several locations depend on TIMER1=0, etc.; don't change the - enumerator values to start at 1. */ -typedef enum { - TIMER1, /*< Advanced control timer TIM1 */ - TIMER2, /*< General purpose timer TIM2 */ - TIMER3, /*< General purpose timer TIM3 */ - TIMER4, /*< General purpose timer TIM4 */ -#ifdef STM32_HIGH_DENSITY - TIMER5, /*< General purpose timer TIM5; high density only */ - /* FIXME maple native: put timers 6 and 7 back in and make the - corresponding changes to timers.c */ - /* TIMER6, /\*< Basic timer TIM6; high density only *\/ */ - /* TIMER7, /\*< Basic timer TIM7; high density only *\/ */ - TIMER8, /*< Advanced control timer TIM8; high density only */ -#endif - TIMER_INVALID /* FIXME: this is starting to seem like a bad idea */ -} timer_dev_num; - -/* timer descriptor */ -struct timer_dev { - timer_port *base; - const uint8 rcc_dev_num; - const uint8 nvic_dev_num; - volatile voidFuncPtr handlers[4]; -}; - -extern struct timer_dev timer_dev_table[]; - -/** - * Initializes timer with prescale as the clock divisor. - * - * @param timer_num Timer number. - * - * @param prescale value in the range 1--65535 to use as a prescaler - * for timer counter increment frequency. - * - * @see timer_dev_num - * @see timer_set_prescaler() - * @see timer_set_mode() - */ -void timer_init(timer_dev_num timer_num, uint16 prescale); - -/** - * Quickly disable all timers. Calling this function is faster than, - * e.g., calling timer_set_mode() for all available timers/channels. - */ -void timer_disable_all(void); - -/** - * Returns the timer's counter value. Due to function call overhead, - * this value is likely to be inaccurate if the counter is running - * with a low prescaler. - * - * @param timer_num the timer whose counter to return. - * - * @pre Timer has been initialized. - */ -uint16 timer_get_count(timer_dev_num timer_num); - -/** - * Sets the counter value for the given timer. - * - * @param timer_num the timer whose counter to set. - * - * @param value the new counter value. - * - * @pre Timer has been initialized. - */ -void timer_set_count(timer_dev_num timer_num, uint16 value); - -/** - * Stops the timer's counter from incrementing. Does not modify the - * timer's mode or settings. - * - * @param timer_num the timer to pause. - * - * @see timer_resume() - * - * @pre Timer has been initialized. - */ -void timer_pause(timer_dev_num timer_num); - -/** - * Starts the counter for the given timer. Does not modify the - * timer's mode or settings. The timer will begin counting on the - * first rising clock cycle after it has been re-enabled using this - * function. - * - * @param timer_num the timer to resume. - * - * @see timer_pause() - * - * @pre Timer has been initialized. - */ -void timer_resume(timer_dev_num timer_num); - -/** - * Returns the prescaler for the given timer. - * - * @param timer_num the timer whose prescaler to return. - * - * @see timer_set_prescaler() - * - * @pre Timer has been initialized. - */ -uint16 timer_get_prescaler(timer_dev_num timer_num); - -/** - * Sets the prescaler for the given timer. This value goes into the - * PSC register, so it's 0-based (i.e., a prescale of 0 counts 1 tick - * per clock cycle). This prescale does not take effect until the - * next update event. - * - * @param timer_num the timer whose prescaler to set. - * - * @param prescale the new prescaler. - * - * @pre Timer has been initialized. - */ -void timer_set_prescaler(timer_dev_num timer_num, uint16 prescale); - -/** - * Gets the reload value for the timer. - * - * @see timer_set_reload() - * - * @pre Timer has been initialized. - */ -uint16 timer_get_reload(timer_dev_num timer_num); - -/** - * Sets the reload value for the timer. - * - * After this function returns, the timer's counter will reset to 0 - * after it has reached the value max_reload. - * - * @pre Timer has been initialized. - */ -void timer_set_reload(timer_dev_num timer_num, uint16 max_reload); - -/* TODO: timer_get_mode */ - -/** - * Set the mode of an individual timer channel. - * - * @see timer_disable_all() - * @see TimerMode - * @see timer_dev_num - * @pre Timer has been initialized. - */ -void timer_set_mode(timer_dev_num timer_num, uint8 channel, TimerMode mode); - -/** - * Get the compare value for the given timer channel. - * @see timer_set_compare_value() - * @see timer_dev_num - * @pre Timer has been initialized. - */ -uint16 timer_get_compare_value(timer_dev_num timer_num, uint8 channel); - -/** - * Sets the compare value for a given timer channel. Useful for - * scheduling when interrupt handlers will be called. - * - * @see timer_attach_interrupt() - * @see timer_detach_interrupt() - * @see timer_set_reload() - * @see timer_dev_num - * @pre Timer has been initialized. - */ -void timer_set_compare_value(timer_dev_num timer_num, uint8 channel, - uint16 value); - -/** - * Detach the interrupt handler for the given timer channel, if any. - * After this function returns, any handler attached to the given - * channel will no longer be called. - * - * @see timer_attach_interrupt() - * @pre Timer has been initialized. - * @see timer_dev_num - */ -void timer_detach_interrupt(timer_dev_num timer_num, uint8 channel); - -/** - * Attach an interrupt handler for the given timer and channel. The - * given ISR, handler, will be called whenever the timer's counter - * reaches the compare value for the given timer and channel. - * - * @see timer_set_compare_value() - * @see timer_detach_interrupt() - * @see timer_set_mode() - * @see timer_dev_num - * @see voidFuncPtr - * @pre Timer has been initialized. - * @pre The channel's mode must be set to TIMER_OUTPUTCOMPARE, or the - * interrupt handler will not get called. - */ -void timer_attach_interrupt(timer_dev_num timer_num, uint8 channel, - voidFuncPtr handler); - -/** - * Programmatically generate an update event on the given timer. This - * updates the prescaler, reloads the compare value (in upcounting - * mode, etc.). - * - * @pre Timer has been initialized. - */ -void timer_generate_update(timer_dev_num timer_num); - -/** - * Turn on PWM with duty_cycle. - * - * @param ccr TIMERx_CHn_CCR, where x ranges over timers, and n ranges - * from 1 to 4. - * - * @param duty_cycle: A number between 0 and - * timer_get_compare_value(TIMERx, y), where x and y are as above. - * - * @pre Pin has been set to alternate function output. - * - * @pre Timer has been initialized. - */ -static inline void timer_pwm_write_ccr(TimerCCR ccr, uint16 duty_cycle) { - *ccr = duty_cycle; -} - -#ifdef __cplusplus -} // extern "C" -#endif - - -#endif - diff --git a/libmaple/util.c b/libmaple/util.c index 09fbecd..6b4f216 100644 --- a/libmaple/util.c +++ b/libmaple/util.c @@ -32,7 +32,7 @@ #include "gpio.h" #include "nvic.h" #include "adc.h" -#include "timers.h" +#include "timer.h" /* Failed asserts send out a message on this USART. */ #ifndef ERROR_USART_NUM diff --git a/libraries/Servo/Servo.h b/libraries/Servo/Servo.h index 1c75618..583312e 100644 --- a/libraries/Servo/Servo.h +++ b/libraries/Servo/Servo.h @@ -28,6 +28,7 @@ #include #include "wirish.h" /* hack for IDE compile */ +#include "HardwareTimer.h" /* Note on Arduino compatibility: diff --git a/notes/portable.txt b/notes/portable.txt index 69952d7..cc1f2ac 100644 --- a/notes/portable.txt +++ b/notes/portable.txt @@ -1,98 +1,28 @@ +Board portability is implemented in boards.h, libmaple.h, and stm32.h. -Disclaimer text: // High-density devices only (Maple Native) +At compile time, we currently expect one of STM32_MEDIUM_DENSITY or +STM32_HIGH_DENSITY to be defined. There's no support for low-density +chips. XL-density isn't in the near horizon; patches welcome. You'll +also need to define some BOARD_foo if you expect to use Wirish; this +comes along with some additional assumptions about your board's layout. +The code in usb/ is not very portable at all right now; expect this to +change in the future, but for now, we're focusing on rolling out a +more complete backend. -Board portability is implemented by adding a header file to ./libmaple with the -name of the BOARD target, and then editing libmaple.h to add this file as an -option. - -A pin maple file should be added to ./notes describing the pin numbering - -Files to check by hand: -# adc.c -# adc.h -# exc.c -# exti.c -# exti.h -# flash.c -# flash.h -# gpio.c -# gpio.h -# libmaple_types.h -# nvic.c -# nvic.h -# rcc.c -# rcc.h -# ring_buffer.h -# rules.mk -# spi.c -- spi.h -# syscalls.c -# systick.c -# systick.h -# timers.c -# timers.h -# usart.c -# usart.h -# util.c -# util.h -# libmaple.h -# usb/* - -wirish/: -# bits.h -# boards.h -# cxxabi-compat.cpp -# ext_interrupts.c -# ext_interrupts.h -# HardwareTimer.cpp -# HardwareTimer.h -# io.h -# main.cxx -# Print.cpp -# Print.h -# pwm.c -# pwm.h -# rules.mk -# time.c -# time.h -# usb_serial.cpp -# usb_serial.h -# wirish_analog.c -# wirish.c -# wirish_digital.c -# wirish.h -# wirish_math.cpp -# wirish_math.h -# wirish_shift.c -# WProgram.h -- comm/ - - - -ADC Notes: - only using ADC1? - untested - -EXTI Notes: - need to update huge table in comments? - untested +A file should be added to ./notes describing the pin numbering of any +new board you add. NVIC Notes: - I don't think NVIC_ISER3 and NVIC_ICER3 actually exist? Only CANBUS and USB OTG use interrupts above #63, but I updated the nvic code anyways RCC Notes: Added some clock stuff to all boards even though they aren't usable... blah. SPI Notes: - SPI3 is only in XL chips so didn't really handle that + SPI3 is only in XL chips, so we don't handle that. TIMER Notes: - High-density devices add an advanced timer (TIMER8) and another normal one (TIMER5). - TIMER6 and TIMER7 are much less useful. - There is some partial progress towards adding timer5/timer8 functionality, - but not much. This should probably all be rewritten. The wirish timer implementation should be refactored to use pin numbers. USART Notes: diff --git a/notes/usb.txt b/notes/usb.txt index 5e00354..9552b9f 100644 --- a/notes/usb.txt +++ b/notes/usb.txt @@ -1,3 +1,7 @@ +XXX +XXX This file may be out of date! +XXX + [NOTE: this is a long term proposal. The current implementation just does a 2ms TIMEOUT] diff --git a/notes/vga.txt b/notes/vga.txt index d75281a..43b6830 100644 --- a/notes/vga.txt +++ b/notes/vga.txt @@ -7,8 +7,7 @@ gpio_write_bit() is about 360ns (2.78MHz) Writing to GPIO?_BASE is about 60ns (16.6MHz -> 18MHz) -pwm write 0x0001 is about 30ns (33MHz) with prescaler as 1 (default) -pwm write 0x0001 is about 14ns (72MHz) with prescaler as 0 (!) +PWM write 0x0001 is about 14ns (72MHz) with prescaler as 0 (!) VGA Timing ------------------------------------------------------------------------------ @@ -34,9 +33,3 @@ Crude 640x480 directions: 11 lines front porch 2 lines Vsync (low) 31 lines back porch - -Currently, setting vs. clearing GPIO registers seems to take a different amount -of time? Or perhaps i'm not analyzing branching correctly. Regardless, if you -SET 100x times then UNSET on one line, then UNSET 100x then SET the next line, -the two changes in color will generally not line up. - diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 66f008f..d99b019 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -1,96 +1,56 @@ #include "boards.h" -// think of the poor column numbers +// For concision #define ADCx ADC_INVALID -#define TIMERx TIMER_INVALID #if defined(BOARD_maple) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* D0/PA3 */ - {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, - /* D1/PA2 */ - {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, - /* D2/PA0 */ - {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, - /* D3/PA1 */ - {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, - /* D4/PB5 */ - {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D5/PB6 */ - {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, - /* D6/PA8 */ - {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, - /* D7/PA9 */ - {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, - /* D8/PA10 */ - {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, - /* D9/PB7 */ - {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, - /* D10/PA4 */ - {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D11/PA7 */ - {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, - /* D12/PA6 */ - {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, - /* D13/PA5 */ - {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D14/PB8 */ - {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, + {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D0/PA3 */ + {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D1/PA2 */ + {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D2/PA0 */ + {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D3/PA1 */ + {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB5 */ + {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D5/PB6 */ + {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D6/PA8 */ + {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D7/PA9 */ + {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D8/PA10 */ + {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D9/PB7 */ + {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D10/PA4 */ + {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D11/PA7 */ + {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D12/PA6 */ + {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D13/PA5 (LED) */ + {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D14/PB8 */ /* Little header */ - /* D15/PC0 */ - {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D16/PC1 */ - {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D17/PC2 */ - {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D18/PC3 */ - {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D19/PC4 */ - {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D20/PC5 */ - {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D15/PC0 */ + {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D16/PC1 */ + {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D17/PC2 */ + {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D18/PC3 */ + {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D19/PC4 */ + {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D20/PC5 */ /* External header */ - /* D21/PC13 */ - {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D22/PC14 */ - {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D23/PC15 */ - {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D24/PB9 */ - {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, - /* D25/PD2 */ - {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D26/PC10 */ - {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D27/PB0 */ - {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, - /* D28/PB1 */ - {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, - /* D29/PB10 */ - {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D30/PB11 */ - {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D31/PB12 */ - {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D32/PB13 */ - {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D33/PB14 */ - {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D34/PB15 */ - {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D35/PC6 */ - {GPIOC, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D36/PC7 */ - {GPIOC, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D37/PC8 */ - {GPIOC, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D38/PC9 (BUT) */ - {GPIOC, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC} + {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC13 */ + {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D22/PC14 */ + {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D23/PC15 */ + {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D24/PB9 */ + {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D25/PD2 */ + {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D26/PC10 */ + {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D27/PB0 */ + {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D28/PB1 */ + {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB10 */ + {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB11 */ + {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ + {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D32/PB13 */ + {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D33/PB14 */ + {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D34/PB15 */ + {GPIOC, 6, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D35/PC6 */ + {GPIOC, 7, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D36/PC7 */ + {GPIOC, 8, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D37/PC8 */ + {GPIOC, 9, ADCx, NULL, 0, AFIO_EXTI_PC} /* D38/PC9 (BUT) */ }; #elif defined(BOARD_maple_native) @@ -98,375 +58,207 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = { PinMapping PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - /* D0/PB10 */ - {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D1/PB2 */ - {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D2/PB12 */ - {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D3/PB13 */ - {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D4/PB14 */ - {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D5/PB15 */ - {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D6/PC0 */ - {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D7/PC1 */ - {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D8/PC2 */ - {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D9/PC3 */ - {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D10/PC4 */ - {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D11/PC5 */ - {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D12/PC6 */ - {GPIOC, 6, ADCx, TIMER8_CH1_CCR, TIMER8, 1, AFIO_EXTI_PC}, - /* D13/PC7 */ - {GPIOC, 7, ADCx, TIMER8_CH2_CCR, TIMER8, 2, AFIO_EXTI_PC}, - /* D14/PC8 */ - {GPIOC, 8, ADCx, TIMER8_CH3_CCR, TIMER8, 3, AFIO_EXTI_PC}, - /* D15/PC9 */ - {GPIOC, 9, ADCx, TIMER8_CH4_CCR, TIMER8, 4, AFIO_EXTI_PC}, - /* D16/PC10 */ - {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D17/PC11 */ - {GPIOC, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D18/PC12 */ - {GPIOC, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D19/PC13 */ - {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D20/PC14 */ - {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D21/PC15 */ - {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D22/PA8 */ - {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, - /* D23/PA9 */ - {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, - /* D24/PA10 */ - {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, - /* D25/PB9 */ - {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, + {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D0/PB10 */ + {GPIOB, 2, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D1/PB2 */ + {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D2/PB12 */ + {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D3/PB13 */ + {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB14 */ + {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D5/PB15 */ + {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D6/PC0 */ + {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D7/PC1 */ + {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D8/PC2 */ + {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D9/PC3 */ + {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D10/PC4 */ + {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D11/PC5 */ + {GPIOC, 6, ADCx, TIMER8, 1, AFIO_EXTI_PC}, /* D12/PC6 */ + {GPIOC, 7, ADCx, TIMER8, 2, AFIO_EXTI_PC}, /* D13/PC7 */ + {GPIOC, 8, ADCx, TIMER8, 3, AFIO_EXTI_PC}, /* D14/PC8 */ + {GPIOC, 9, ADCx, TIMER8, 4, AFIO_EXTI_PC}, /* D15/PC9 */ + {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D16/PC10 */ + {GPIOC, 11, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D17/PC11 */ + {GPIOC, 12, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D18/PC12 */ + {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D19/PC13 */ + {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D20/PC14 */ + {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC15 */ + {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D22/PA8 */ + {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D23/PA9 */ + {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D24/PA10 */ + {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D25/PB9 */ /* Bottom header */ + /* FIXME (?) What about D48--D50 also being TIMER2_CH[234]? */ - /* D26/PD2 */ - {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D27/PD3 */ - {GPIOD, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D28/PD6 */ - {GPIOD, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D29/PG11 */ - {GPIOG, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D30/PG12 */ - {GPIOG, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D31/PG13 */ - {GPIOG, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D32/PG14 */ - {GPIOG, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D33/PG8 */ - {GPIOG, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D34/PG7 */ - {GPIOG, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D35/PG6 */ - {GPIOG, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D36/PB5 */ - {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D37/PB6 */ - {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, - /* D38/PB7 */ - {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, - /* D39/PF6 */ - {GPIOF, 6, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D40/PF7 */ - {GPIOF, 7, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D41/PF8 */ - {GPIOF, 8, 6, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D42/PF9 */ - {GPIOF, 9, 7, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D43/PF10 */ - {GPIOF, 10, 8, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D44/PF11 */ - {GPIOF, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D45/PB1 */ - {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, - /* D46/PB0 */ - {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, - /* D47/PA0 */ - {GPIOA, 0, 0, TIMER5_CH1_CCR, TIMER5, 1, AFIO_EXTI_PA}, - /* D48/PA1 */ /* FIXME (?) - What about D48--D50 also being TIMER2_CH[234]? */ - {GPIOA, 1, 1, TIMER5_CH2_CCR, TIMER5, 2, AFIO_EXTI_PA}, - /* D49/PA2 */ - {GPIOA, 2, 2, TIMER5_CH3_CCR, TIMER5, 3, AFIO_EXTI_PA}, - /* D50/PA3 */ - {GPIOA, 3, 3, TIMER5_CH4_CCR, TIMER5, 4, AFIO_EXTI_PA}, - /* D51/PA4 */ - {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D52/PA5 */ - {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D53/PA6 */ - {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, - /* D54/PA7 */ - {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, + {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D26/PD2 */ + {GPIOD, 3, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D27/PD3 */ + {GPIOD, 6, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D28/PD6 */ + {GPIOG, 11, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D29/PG11 */ + {GPIOG, 12, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D30/PG12 */ + {GPIOG, 13, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D31/PG13 */ + {GPIOG, 14, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D32/PG14 */ + {GPIOG, 8, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D33/PG8 */ + {GPIOG, 7, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D34/PG7 */ + {GPIOG, 6, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D35/PG6 */ + {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D36/PB5 */ + {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D37/PB6 */ + {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D38/PB7 */ + {GPIOF, 6, 4, NULL, 0, AFIO_EXTI_PF}, /* D39/PF6 */ + {GPIOF, 7, 5, NULL, 0, AFIO_EXTI_PF}, /* D40/PF7 */ + {GPIOF, 8, 6, NULL, 0, AFIO_EXTI_PF}, /* D41/PF8 */ + {GPIOF, 9, 7, NULL, 0, AFIO_EXTI_PF}, /* D42/PF9 */ + {GPIOF, 10, 8, NULL, 0, AFIO_EXTI_PF}, /* D43/PF10 */ + {GPIOF, 11, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D44/PF11 */ + {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D45/PB1 */ + {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D46/PB0 */ + {GPIOA, 0, 0, TIMER5, 1, AFIO_EXTI_PA}, /* D47/PA0 */ + {GPIOA, 1, 1, TIMER5, 2, AFIO_EXTI_PA}, /* D48/PA1 */ + {GPIOA, 2, 2, TIMER5, 3, AFIO_EXTI_PA}, /* D49/PA2 */ + {GPIOA, 3, 3, TIMER5, 4, AFIO_EXTI_PA}, /* D50/PA3 */ + {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D51/PA4 */ + {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D52/PA5 */ + {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D53/PA6 */ + {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D54/PA7 */ /* Right (triple) header */ - /* D55/PF0 */ - {GPIOF, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D56/PD11 */ - {GPIOD, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D57/PD14 */ - {GPIOD, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D58/PF1 */ - {GPIOF, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D59/PD12 */ - {GPIOD, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D60/PD15 */ - {GPIOD, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D61/PF2 */ - {GPIOF, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D62/PD13 */ - {GPIOD, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D63/PD0 */ - {GPIOD, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D64/PF3 */ - {GPIOF, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D65/PE3 */ - {GPIOE, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D66/PD1 */ - {GPIOD, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D67/PF4 */ - {GPIOF, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D68/PE4 */ - {GPIOE, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D69/PE7 */ - {GPIOE, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D70/PF5 */ - {GPIOF, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D71/PE5 */ - {GPIOE, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D72/PE8 */ - {GPIOE, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D73/PF12 */ - {GPIOF, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D74/PE6 */ - {GPIOE, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D75/PE9 */ - {GPIOE, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D76/PF13 */ - {GPIOF, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D77/PE10 */ - {GPIOE, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D78/PF14 */ - {GPIOF, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D79/PG9 */ - {GPIOG, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D80/PE11 */ - {GPIOE, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D81/PF15 */ - {GPIOF, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF}, - /* D82/PG10 */ - {GPIOG, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D83/PE12 */ - {GPIOE, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D84/PG0 */ - {GPIOG, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D85/PD5 */ - {GPIOD, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D86/PE13 */ - {GPIOE, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D87/PG1 */ - {GPIOG, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D88/PD4 */ - {GPIOD, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D89/PE14 */ - {GPIOE, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D90/PG2 */ - {GPIOG, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D91/PE1 */ - {GPIOE, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D92/PE15 */ - {GPIOE, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D93/PG3 */ - {GPIOG, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D94/PE0 */ - {GPIOE, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE}, - /* D95/PD8 */ - {GPIOD, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D96/PG4 */ - {GPIOG, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D97/PD9 */ - {GPIOD, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D98/PG5 */ - {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG}, - /* D99/PD10 */ - {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD} + {GPIOF, 0, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D55/PF0 */ + {GPIOD, 11, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D56/PD11 */ + {GPIOD, 14, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D57/PD14 */ + {GPIOF, 1, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D58/PF1 */ + {GPIOD, 12, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D59/PD12 */ + {GPIOD, 15, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D60/PD15 */ + {GPIOF, 2, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D61/PF2 */ + {GPIOD, 13, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D62/PD13 */ + {GPIOD, 0, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D63/PD0 */ + {GPIOF, 3, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D64/PF3 */ + {GPIOE, 3, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D65/PE3 */ + {GPIOD, 1, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D66/PD1 */ + {GPIOF, 4, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D67/PF4 */ + {GPIOE, 4, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D68/PE4 */ + {GPIOE, 7, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D69/PE7 */ + {GPIOF, 5, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D70/PF5 */ + {GPIOE, 5, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D71/PE5 */ + {GPIOE, 8, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D72/PE8 */ + {GPIOF, 12, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D73/PF12 */ + {GPIOE, 6, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D74/PE6 */ + {GPIOE, 9, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D75/PE9 */ + {GPIOF, 13, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D76/PF13 */ + {GPIOE, 10, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D77/PE10 */ + {GPIOF, 14, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D78/PF14 */ + {GPIOG, 9, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D79/PG9 */ + {GPIOE, 11, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D80/PE11 */ + {GPIOF, 15, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D81/PF15 */ + {GPIOG, 10, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D82/PG10 */ + {GPIOE, 12, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D83/PE12 */ + {GPIOG, 0, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D84/PG0 */ + {GPIOD, 5, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D85/PD5 */ + {GPIOE, 13, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D86/PE13 */ + {GPIOG, 1, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D87/PG1 */ + {GPIOD, 4, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D88/PD4 */ + {GPIOE, 14, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D89/PE14 */ + {GPIOG, 2, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D90/PG2 */ + {GPIOE, 1, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D91/PE1 */ + {GPIOE, 15, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D92/PE15 */ + {GPIOG, 3, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D93/PG3 */ + {GPIOE, 0, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D94/PE0 */ + {GPIOD, 8, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D95/PD8 */ + {GPIOG, 4, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D96/PG4 */ + {GPIOD, 9, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D97/PD9 */ + {GPIOG, 5, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D98/PG5 */ + {GPIOD, 10, ADCx, NULL, 0, AFIO_EXTI_PD} /* D99/PD10 */ }; #elif defined(BOARD_maple_mini) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* D0/PB11 */ - {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D1/PB10 */ - {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D2/PB2 */ - {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D3/PB0 */ - {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, - /* D4/PA7 */ - {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, - /* D5/PA6 */ - {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, - /* D6/PA5 */ - {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D7/PA4 */ - {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D8/PA3 */ - {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, - /* D9/PA2 */ - {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, - /* D10/PA1 */ - {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, - /* D11/PA0 */ - {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, - /* D12/PC15 */ - {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D13/PC14 */ - {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D14/PC13 */ - {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D15/PB7 */ - {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, - /* D16/PB6 */ - {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, - /* D17/PB5 */ - {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D18/PB4 */ - {GPIOB, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D19/PB3 */ - {GPIOB, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D20/PA15 */ - {GPIOA, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D21/PA14 */ - {GPIOA, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D22/PA13 */ - {GPIOA, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D23/PA12 */ - {GPIOA, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D24/PA11 */ - {GPIOA, 11, ADCx, TIMER1_CH4_CCR, TIMER1, 4, AFIO_EXTI_PA}, - /* D25/PA10 */ - {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, - /* D26/PA9 */ - {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, - /* D27/PA8 */ - {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, - /* D28/PB15 */ - {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D29/PB14 */ - {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D30/PB13 */ - {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D31/PB12 */ - {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D32/PB8 */ - {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, - /* D33/PB1 */ - {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, + /* Top header */ + + {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D0/PB11 */ + {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D1/PB10 */ + {GPIOB, 2, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D2/PB2 */ + {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D3/PB0 */ + {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D4/PA7 */ + {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D5/PA6 */ + {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D6/PA5 */ + {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D7/PA4 */ + {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D8/PA3 */ + {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D9/PA2 */ + {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D10/PA1 */ + {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D11/PA0 */ + {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D12/PC15 */ + {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D13/PC14 */ + {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D14/PC13 */ + + /* Bottom header */ + + {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D15/PB7 */ + {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D16/PB6 */ + {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D17/PB5 */ + {GPIOB, 4, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D18/PB4 */ + {GPIOB, 3, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D19/PB3 */ + {GPIOA, 15, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D20/PA15 */ + {GPIOA, 14, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D21/PA14 */ + {GPIOA, 13, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D22/PA13 */ + {GPIOA, 12, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D23/PA12 */ + {GPIOA, 11, ADCx, TIMER1, 4, AFIO_EXTI_PA}, /* D24/PA11 */ + {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D25/PA10 */ + {GPIOA, 9, ADCx, TIMER2, 2, AFIO_EXTI_PA}, /* D26/PA9 */ + {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D27/PA8 */ + {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D28/PB15 */ + {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB14 */ + {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB13 */ + {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ + {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D32/PB8 */ + {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D33/PB1 */ }; #elif defined(BOARD_maple_RET6) PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* D0/PA3 */ - {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA}, - /* D1/PA2 */ - {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA}, - /* D2/PA0 */ - {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA}, - /* D3/PA1 */ - {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA}, - /* D4/PB5 */ - {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D5/PB6 */ - {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB}, - /* D6/PA8 */ - {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA}, - /* D7/PA9 */ - {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA}, - /* D8/PA10 */ - {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA}, - /* D9/PB7 */ - {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB}, - /* D10/PA4 */ - {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D11/PA7 */ - {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA}, - /* D12/PA6 */ - {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA}, - /* D13/PA5 */ - {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA}, - /* D14/PB8 */ - {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB}, + {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D0/PA3 */ + {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D1/PA2 */ + {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D2/PA0 */ + {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D3/PA1 */ + {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB5 */ + {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D5/PB6 */ + {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D6/PA8 */ + {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D7/PA9 */ + {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D8/PA10 */ + {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D9/PB7 */ + {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D10/PA4 */ + {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D11/PA7 */ + {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D12/PA6 */ + {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D13/PA5 (LED) */ + {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D14/PB8 */ /* Little header */ - /* D15/PC0 */ - {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D16/PC1 */ - {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D17/PC2 */ - {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D18/PC3 */ - {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D19/PC4 */ - {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D20/PC5 */ - {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, + {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D15/PC0 */ + {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D16/PC1 */ + {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D17/PC2 */ + {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D18/PC3 */ + {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D19/PC4 */ + {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D20/PC5 */ /* External header */ - /* D21/PC13 */ - {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D22/PC14 */ - {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D23/PC15 */ - {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D24/PB9 */ - {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB}, - /* D25/PD2 */ - {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}, - /* D26/PC10 */ - {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}, - /* D27/PB0 */ - {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB}, - /* D28/PB1 */ - {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB}, - /* D29/PB10 */ - {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D30/PB11 */ - {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D31/PB12 */ - {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D32/PB13 */ - {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D33/PB14 */ - {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D34/PB15 */ - {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB}, - /* D35/PC6 */ - {GPIOC, 6, ADCx, TIMER8_CH1_CCR, TIMER8, 1, AFIO_EXTI_PC}, - /* D36/PC7 */ - {GPIOC, 7, ADCx, TIMER8_CH1_CCR, TIMER8, 2, AFIO_EXTI_PC}, - /* D37/PC8 */ - {GPIOC, 8, ADCx, TIMER8_CH1_CCR, TIMER8, 3, AFIO_EXTI_PC}, - /* D38/PC9 (BUT) */ - {GPIOC, 9, ADCx, TIMER8_CH1_CCR, TIMER8, 4, AFIO_EXTI_PC} + {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC13 */ + {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D22/PC14 */ + {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D23/PC15 */ + {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D24/PB9 */ + {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D25/PD2 */ + {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D26/PC10 */ + {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D27/PB0 */ + {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D28/PB1 */ + {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB10 */ + {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB11 */ + {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ + {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D32/PB13 */ + {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D33/PB14 */ + {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D34/PB15 */ + {GPIOC, 6, ADCx, TIMER8, 1, AFIO_EXTI_PC}, /* D35/PC6 */ + {GPIOC, 7, ADCx, TIMER8, 2, AFIO_EXTI_PC}, /* D36/PC7 */ + {GPIOC, 8, ADCx, TIMER8, 3, AFIO_EXTI_PC}, /* D37/PC8 */ + {GPIOC, 9, ADCx, TIMER8, 4, AFIO_EXTI_PC} /* D38/PC9 (BUT) */ }; #else diff --git a/wirish/boards.h b/wirish/boards.h index 94566fa..d186dc4 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -33,7 +33,8 @@ #include "libmaple.h" #include "gpio.h" -#include "timers.h" +#include "timer.h" +#include "native_sram.h" /* Set of all possible pin names; not all boards have all these (note that we use the Dx convention since all of the Maple's pins are @@ -56,9 +57,8 @@ typedef struct PinMapping { gpio_dev *gpio_device; uint32 pin; uint32 adc_channel; - TimerCCR timer_ccr; - timer_dev_num timer_num; - uint32 timer_chan; + timer_dev* timer_device; + uint8 timer_chan; afio_exti_port ext_port; } PinMapping; @@ -94,6 +94,7 @@ extern PinMapping PIN_MAP[]; #define NR_GPIO_PINS 100 #define BOARD_INIT do { \ + initNativeSRAM(); } while(0) #elif defined(BOARD_maple_mini) diff --git a/wirish/comm/HardwareSPI.cpp b/wirish/comm/HardwareSPI.cpp index 20090f5..aea7734 100644 --- a/wirish/comm/HardwareSPI.cpp +++ b/wirish/comm/HardwareSPI.cpp @@ -47,8 +47,10 @@ * TODO: Do the complementary PWM outputs mess up SPI2? * */ -#include "wirish.h" #include "spi.h" +#include "timer.h" + +#include "wirish.h" #include "HardwareSPI.h" static const uint32 prescaleFactors[MAX_SPI_FREQS] = { diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp index 08252d8..97a5ec3 100644 --- a/wirish/comm/HardwareSerial.cpp +++ b/wirish/comm/HardwareSerial.cpp @@ -31,12 +31,10 @@ #include "wirish.h" #include "HardwareSerial.h" #include "usart.h" -#include "gpio.h" -#include "timers.h" -HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9,10, TIMER1, 2); -HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3); -HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10,11, TIMER_INVALID, 0); +HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9, 10, TIMER1, 2); +HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3); +HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10, 11, NULL, 0); // TODO: High density device ports HardwareSerial::HardwareSerial(uint8 usart_num, @@ -44,15 +42,15 @@ HardwareSerial::HardwareSerial(uint8 usart_num, gpio_dev *gpio_device, uint8 tx_pin, uint8 rx_pin, - timer_dev_num timer_num, - uint8 compare_num) { + timer_dev *timer_device, + uint8 channel_num) { this->usart_num = usart_num; this->max_baud = max_baud; this->gpio_device = gpio_device; this->tx_pin = tx_pin; this->rx_pin = rx_pin; - this->timer_num = timer_num; - this->compare_num = compare_num; + this->timer_device = timer_device; + this->channel_num = channel_num; } uint8 HardwareSerial::read(void) { @@ -75,9 +73,9 @@ void HardwareSerial::begin(uint32 baud) { gpio_set_mode(gpio_device, tx_pin, GPIO_AF_OUTPUT_PP); gpio_set_mode(gpio_device, rx_pin, GPIO_INPUT_FLOATING); - if (timer_num != TIMER_INVALID) { + if (timer_device != NULL) { /* turn off any pwm if there's a conflict on this usart */ - timer_set_mode(timer_num, compare_num, TIMER_DISABLED); + timer_set_mode(timer_device, channel_num, TIMER_DISABLED); } usart_init(usart_num, baud); diff --git a/wirish/comm/HardwareSerial.h b/wirish/comm/HardwareSerial.h index ef19a56..7852d51 100644 --- a/wirish/comm/HardwareSerial.h +++ b/wirish/comm/HardwareSerial.h @@ -31,7 +31,9 @@ #ifndef _HARDWARESERIAL_H_ #define _HARDWARESERIAL_H_ -#include "timers.h" +#include "libmaple_types.h" +#include "gpio.h" +#include "timer.h" #include "Print.h" @@ -49,16 +51,16 @@ class HardwareSerial : public Print { gpio_dev *gpio_device; uint8 tx_pin; uint8 rx_pin; - timer_dev_num timer_num; - uint8 compare_num; + timer_dev *timer_device; + uint8 channel_num; public: HardwareSerial(uint8 usart_num, uint32 max_baud, gpio_dev *gpio_device, uint8 tx_pin, uint8 rx_pin, - timer_dev_num timer_num, - uint8 compare_num); + timer_dev *timer_device, + uint8 channel_num); void begin(uint32 baud); void end(void); uint32 available(void); diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp index 072e4cd..6b09cef 100644 --- a/wirish/pwm.cpp +++ b/wirish/pwm.cpp @@ -23,26 +23,20 @@ *****************************************************************************/ /** - * @brief Arduino-compatible PWM implementation. + * @brief Arduino-style PWM implementation. */ -#include "wirish.h" -#include "timers.h" -#include "io.h" +#include "libmaple_types.h" +#include "timer.h" + +#include "boards.h" #include "pwm.h" void pwmWrite(uint8 pin, uint16 duty_cycle) { - TimerCCR ccr; - - if (pin >= NR_GPIO_PINS) { - return; - } - - ccr = PIN_MAP[pin].timer_ccr; - - if (ccr == 0) { + timer_dev *dev = PIN_MAP[pin].timer_device; + if (pin >= NR_GPIO_PINS || dev == NULL || dev->type == TIMER_BASIC) { return; } - timer_pwm_write_ccr(ccr, duty_cycle); + timer_set_compare(dev, PIN_MAP[pin].timer_chan, duty_cycle); } diff --git a/wirish/rules.mk b/wirish/rules.mk index 3dd4b2d..d250cb9 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -18,7 +18,6 @@ cppSRCS_$(d) := wirish_math.cpp \ comm/HardwareSerial.cpp \ comm/HardwareSPI.cpp \ usb_serial.cpp \ - HardwareTimer.cpp \ cxxabi-compat.cpp \ wirish.cpp \ wirish_shift.cpp \ diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index 65d0262..6dcb1b5 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -23,61 +23,107 @@ *****************************************************************************/ /** - * @brief generic maple board bring up: + * @brief Generic Maple board initialization. * - * By default, we bring up all maple boards running on the stm32 to 72mhz, - * clocked off the PLL, driven by the 8MHz external crystal. - * - * AHB and APB2 are clocked at 72MHz - * APB1 is clocked at 36MHz + * By default, we bring up all Maple boards to 72MHz, clocked off the + * PLL, driven by the 8MHz external crystal. AHB and APB2 are clocked + * at 72MHz. APB1 is clocked at 36MHz. */ #include "wirish.h" + +#include "flash.h" +#include "rcc.h" +#include "nvic.h" #include "systick.h" #include "gpio.h" -#include "nvic.h" +#include "adc.h" +#include "timer.h" #include "usb.h" -#include "rcc.h" -#include "fsmc.h" -#include "dac.h" -#include "flash.h" -#include "native_sram.h" +static void setupFlash(void); +static void setupClocks(void); +static void setupADC(void); +static void setupTimers(void); + +/** + * Board-wide initialization function. Called before main(). + */ void init(void) { - /* make sure the flash is ready before spinning the high speed clock up */ + setupFlash(); + setupClocks(); + nvic_init(); + systick_init(SYSTICK_RELOAD_VAL); + gpio_init_all(); + afio_init(); + setupADC(); + setupTimers(); + setupUSB(); + + BOARD_INIT; +} + +static void setupFlash(void) { flash_enable_prefetch(); flash_set_latency(FLASH_WAIT_STATE_2); +} -#ifdef BOARD_maple_native - initNativeSRAM(); -#endif - - /* initialize clocks */ +/* + * Clock setup. Note that some of this only takes effect if we're + * running bare metal and the bootloader hasn't done it for us + * already. + * + * If you change this function, you MUST change the file-level Doxygen + * comment above. + */ +static void setupClocks() { rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); +} - nvic_init(); - systick_init(SYSTICK_RELOAD_VAL); - gpio_init_all(); - afio_init(); - - /* Initialize the ADC for slow conversions, to allow for high - impedance inputs. */ +/* TODO initialize more ADCs on high density boards. */ +static void setupADC() { adc_init(ADC1, 0); - adc_set_sample_rate(ADC1, ADC_SMPR_55_5); - - timer_init(TIMER1, 1); - timer_init(TIMER2, 1); - timer_init(TIMER3, 1); - timer_init(TIMER4, 1); -#ifdef STM32_HIGH_DENSITY - timer_init(TIMER5, 1); - timer_init(TIMER8, 1); -#endif - setupUSB(); + adc_set_sample_rate(ADC1, ADC_SMPR_55_5); // for high impedance inputs +} - /* include the board-specific init macro */ - BOARD_INIT; +static void timerDefaultConfig(timer_dev*); + +static void setupTimers() { + timer_foreach(timerDefaultConfig); +} + +static void timerDefaultConfig(timer_dev *dev) { + timer_adv_reg_map *regs = (dev->regs).adv; + const uint16 full_overflow = 0xFFFF; + const uint16 half_duty = 0x8FFF; + + timer_init(dev); + timer_pause(dev); + + regs->CR1 = TIMER_CR1_ARPE; + regs->PSC = 1; + regs->SR = 0; + regs->DIER = 0; + regs->EGR = TIMER_EGR_UG; + + switch (dev->type) { + case TIMER_ADVANCED: + regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; + // fall-through + case TIMER_GENERAL: + timer_set_reload(dev, full_overflow); + + for (int channel = 1; channel <= 4; channel++) { + timer_set_compare(dev, channel, half_duty); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, TIMER_OC_PE); + } + // fall-through + case TIMER_BASIC: + break; + } + + timer_resume(dev); } diff --git a/wirish/wirish.h b/wirish/wirish.h index 447b2b6..319df97 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -32,7 +32,6 @@ #define _WIRISH_H_ #include "libmaple.h" -#include "timers.h" #include "boards.h" #include "io.h" @@ -44,7 +43,6 @@ #include "HardwareSPI.h" #include "HardwareSerial.h" #include "usb_serial.h" -#include "HardwareTimer.h" /* Arduino wiring macros and bit defines */ #define HIGH 0x1 @@ -69,7 +67,6 @@ typedef uint8 boolean; typedef uint8 byte; void init(void); -void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, byte val); #endif diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp index 0c0bd85..4b68861 100644 --- a/wirish/wirish_digital.cpp +++ b/wirish/wirish_digital.cpp @@ -72,15 +72,15 @@ void pinMode(uint8 pin, WiringPinMode mode) { gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, outputMode); - if (PIN_MAP[pin].timer_num != TIMER_INVALID) { + if (PIN_MAP[pin].timer_device != NULL) { /* enable/disable timer channels if we're switching into or out of pwm */ if (pwm) { - timer_set_mode(PIN_MAP[pin].timer_num, + timer_set_mode(PIN_MAP[pin].timer_device, PIN_MAP[pin].timer_chan, TIMER_PWM); } else { - timer_set_mode(PIN_MAP[pin].timer_num, + timer_set_mode(PIN_MAP[pin].timer_device, PIN_MAP[pin].timer_chan, TIMER_DISABLED); } -- cgit v1.2.3 From 63ea7464925b8cbeb8623d08a2bde0b1d2044047 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Thu, 24 Mar 2011 17:27:38 -0400 Subject: Adding /wirish/boards/ for easier porting; shrank PIN_MAPs. /wirish/boards/ contains xxx.h and xxx.cpp (for xxx=maple, maple_native, maple_mini, maple_RET6). The headers contain the board-specific #defines that used to live in boards.h (except BOARD_INIT, which was removed). The CPP files contain the PIN_MAP definitions that used to live in boards.cpp, and a proper boardInit() function to replace the old BOARD_INIT macro. This will make it easier to add new boards in the future. struct PinMapping was renamed struct stm32_pin_info, and was moved into a new wirish_types.h. Its external interrupt field was moved into struct gpio_dev, which saves memory by storing an afio_exti_port per port, rather than one per pin. Also rearranged the stm32_pin_info fields to improve packing. Maple's PIN_MAP is now down to below 500 bytes. --- examples/test-session.cpp | 2 +- libmaple/gpio.c | 35 +++--- libmaple/gpio.h | 59 +++++---- wirish/boards.cpp | 268 ----------------------------------------- wirish/boards.h | 144 ++++++++-------------- wirish/boards/maple.cpp | 94 +++++++++++++++ wirish/boards/maple.h | 59 +++++++++ wirish/boards/maple_RET6.cpp | 88 ++++++++++++++ wirish/boards/maple_RET6.h | 61 ++++++++++ wirish/boards/maple_mini.cpp | 87 +++++++++++++ wirish/boards/maple_mini.h | 60 +++++++++ wirish/boards/maple_native.cpp | 155 ++++++++++++++++++++++++ wirish/boards/maple_native.h | 64 ++++++++++ wirish/ext_interrupts.cpp | 6 +- wirish/rules.mk | 10 +- wirish/wirish.cpp | 3 +- wirish/wirish.h | 1 + wirish/wirish_analog.cpp | 2 +- wirish/wirish_digital.cpp | 8 +- wirish/wirish_types.h | 51 ++++++++ 20 files changed, 840 insertions(+), 417 deletions(-) delete mode 100644 wirish/boards.cpp create mode 100644 wirish/boards/maple.cpp create mode 100644 wirish/boards/maple.h create mode 100644 wirish/boards/maple_RET6.cpp create mode 100644 wirish/boards/maple_RET6.h create mode 100644 wirish/boards/maple_mini.cpp create mode 100644 wirish/boards/maple_mini.h create mode 100644 wirish/boards/maple_native.cpp create mode 100644 wirish/boards/maple_native.h create mode 100644 wirish/wirish_types.h (limited to 'wirish') diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 9b4bce4..28c02f3 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -351,7 +351,7 @@ void cmd_everything(void) { // TODO void fast_gpio(int maple_pin) { gpio_dev *dev = PIN_MAP[maple_pin].gpio_device; - uint32 pin = PIN_MAP[maple_pin].pin; + uint32 pin = PIN_MAP[maple_pin].gpio_pin; gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); diff --git a/libmaple/gpio.c b/libmaple/gpio.c index 18b856b..5484e21 100644 --- a/libmaple/gpio.c +++ b/libmaple/gpio.c @@ -34,45 +34,52 @@ */ gpio_dev gpioa = { - .regs = GPIOA_BASE, - .clk_id = RCC_GPIOA + .regs = GPIOA_BASE, + .clk_id = RCC_GPIOA, + .exti_port = AFIO_EXTI_PA, }; gpio_dev* const GPIOA = &gpioa; gpio_dev gpiob = { - .regs = GPIOB_BASE, - .clk_id = RCC_GPIOB + .regs = GPIOB_BASE, + .clk_id = RCC_GPIOB, + .exti_port = AFIO_EXTI_PB, }; gpio_dev* const GPIOB = &gpiob; gpio_dev gpioc = { - .regs = GPIOC_BASE, - .clk_id = RCC_GPIOC + .regs = GPIOC_BASE, + .clk_id = RCC_GPIOC, + .exti_port = AFIO_EXTI_PC, }; gpio_dev* const GPIOC = &gpioc; gpio_dev gpiod = { - .regs = GPIOD_BASE, - .clk_id = RCC_GPIOD + .regs = GPIOD_BASE, + .clk_id = RCC_GPIOD, + .exti_port = AFIO_EXTI_PD, }; gpio_dev* const GPIOD = &gpiod; #ifdef STM32_HIGH_DENSITY gpio_dev gpioe = { - .regs = GPIOE_BASE, - .clk_id = RCC_GPIOE + .regs = GPIOE_BASE, + .clk_id = RCC_GPIOE, + .exti_port = AFIO_EXTI_PE, }; gpio_dev* const GPIOE = &gpioe; gpio_dev gpiof = { - .regs = GPIOF_BASE, - .clk_id = RCC_GPIOF + .regs = GPIOF_BASE, + .clk_id = RCC_GPIOF, + .exti_port = AFIO_EXTI_PF, }; gpio_dev* const GPIOF = &gpiof; gpio_dev gpiog = { - .regs = GPIOG_BASE, - .clk_id = RCC_GPIOG + .regs = GPIOG_BASE, + .clk_id = RCC_GPIOG, + .exti_port = AFIO_EXTI_PG, }; gpio_dev* const GPIOG = &gpiog; #endif diff --git a/libmaple/gpio.h b/libmaple/gpio.h index a8a4985..63ba0d5 100644 --- a/libmaple/gpio.h +++ b/libmaple/gpio.h @@ -47,19 +47,37 @@ extern "C"{ /** GPIO register map type */ typedef struct gpio_reg_map { - __io uint32 CRL; ///< Port configuration register low - __io uint32 CRH; ///< Port configuration register high - __io uint32 IDR; ///< Port input data register - __io uint32 ODR; ///< Port output data register - __io uint32 BSRR; ///< Port bit set/reset register - __io uint32 BRR; ///< Port bit reset register - __io uint32 LCKR; ///< Port configuration lock register + __io uint32 CRL; /**< Port configuration register low */ + __io uint32 CRH; /**< Port configuration register high */ + __io uint32 IDR; /**< Port input data register */ + __io uint32 ODR; /**< Port output data register */ + __io uint32 BSRR; /**< Port bit set/reset register */ + __io uint32 BRR; /**< Port bit reset register */ + __io uint32 LCKR; /**< Port configuration lock register */ } gpio_reg_map; + +/** + * External interrupt line port selector. Used to determine which + * GPIO port to map an external interrupt line onto. */ +/* (See AFIO sections, below) */ +typedef enum { + AFIO_EXTI_PA, /**< Use PAx pin. */ + AFIO_EXTI_PB, /**< Use PBx pin. */ + AFIO_EXTI_PC, /**< Use PCx pin. */ + AFIO_EXTI_PD, /**< Use PDx pin. */ +#ifdef STM32_HIGH_DENSITY + AFIO_EXTI_PE, /**< Use PEx pin. */ + AFIO_EXTI_PF, /**< Use PFx pin. */ + AFIO_EXTI_PG, /**< Use PGx pin. */ +#endif +} afio_exti_port; + /** GPIO device type */ typedef struct gpio_dev { - gpio_reg_map *regs; ///< Register map - rcc_clk_id clk_id; ///< RCC clock information + gpio_reg_map *regs; /**< Register map */ + rcc_clk_id clk_id; /**< RCC clock information */ + afio_exti_port exti_port; /**< AFIO external interrupt port value */ } gpio_dev; extern gpio_dev gpioa; @@ -144,6 +162,14 @@ void gpio_init(gpio_dev *dev); void gpio_init_all(void); void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode); +/** + * @brief Get a GPIO port's corresponding afio_exti_port. + * @param dev GPIO device whose afio_exti_port to return. + */ +static inline afio_exti_port gpio_exti_port(gpio_dev *dev) { + return dev->exti_port; +} + /** * Set or reset a GPIO pin. * @@ -259,21 +285,6 @@ typedef struct afio_reg_map { /* External interrupt configuration registers */ -/** - * External interrupt line port selector. Used to determine which - * GPIO port to map an external interrupt line onto. */ -typedef enum { - AFIO_EXTI_PA, /**< Use PAx pin. */ - AFIO_EXTI_PB, /**< Use PBx pin. */ - AFIO_EXTI_PC, /**< Use PCx pin. */ - AFIO_EXTI_PD, /**< Use PDx pin. */ -#ifdef STM32_HIGH_DENSITY - AFIO_EXTI_PE, /**< Use PEx pin. */ - AFIO_EXTI_PF, /**< Use PFx pin. */ - AFIO_EXTI_PG, /**< Use PGx pin. */ -#endif -} afio_exti_port; - /** * External interrupt line numbers. */ diff --git a/wirish/boards.cpp b/wirish/boards.cpp deleted file mode 100644 index d99b019..0000000 --- a/wirish/boards.cpp +++ /dev/null @@ -1,268 +0,0 @@ -#include "boards.h" - -// For concision -#define ADCx ADC_INVALID - -#if defined(BOARD_maple) - -PinMapping PIN_MAP[NR_GPIO_PINS] = { - {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D0/PA3 */ - {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D1/PA2 */ - {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D2/PA0 */ - {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D3/PA1 */ - {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB5 */ - {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D5/PB6 */ - {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D6/PA8 */ - {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D7/PA9 */ - {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D8/PA10 */ - {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D9/PB7 */ - {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D10/PA4 */ - {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D11/PA7 */ - {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D12/PA6 */ - {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D13/PA5 (LED) */ - {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D14/PB8 */ - - /* Little header */ - - {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D15/PC0 */ - {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D16/PC1 */ - {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D17/PC2 */ - {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D18/PC3 */ - {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D19/PC4 */ - {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D20/PC5 */ - - /* External header */ - - {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC13 */ - {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D22/PC14 */ - {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D23/PC15 */ - {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D24/PB9 */ - {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D25/PD2 */ - {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D26/PC10 */ - {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D27/PB0 */ - {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D28/PB1 */ - {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB10 */ - {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB11 */ - {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ - {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D32/PB13 */ - {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D33/PB14 */ - {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D34/PB15 */ - {GPIOC, 6, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D35/PC6 */ - {GPIOC, 7, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D36/PC7 */ - {GPIOC, 8, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D37/PC8 */ - {GPIOC, 9, ADCx, NULL, 0, AFIO_EXTI_PC} /* D38/PC9 (BUT) */ -}; - -#elif defined(BOARD_maple_native) - -PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* Top header */ - - {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D0/PB10 */ - {GPIOB, 2, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D1/PB2 */ - {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D2/PB12 */ - {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D3/PB13 */ - {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB14 */ - {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D5/PB15 */ - {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D6/PC0 */ - {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D7/PC1 */ - {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D8/PC2 */ - {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D9/PC3 */ - {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D10/PC4 */ - {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D11/PC5 */ - {GPIOC, 6, ADCx, TIMER8, 1, AFIO_EXTI_PC}, /* D12/PC6 */ - {GPIOC, 7, ADCx, TIMER8, 2, AFIO_EXTI_PC}, /* D13/PC7 */ - {GPIOC, 8, ADCx, TIMER8, 3, AFIO_EXTI_PC}, /* D14/PC8 */ - {GPIOC, 9, ADCx, TIMER8, 4, AFIO_EXTI_PC}, /* D15/PC9 */ - {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D16/PC10 */ - {GPIOC, 11, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D17/PC11 */ - {GPIOC, 12, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D18/PC12 */ - {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D19/PC13 */ - {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D20/PC14 */ - {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC15 */ - {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D22/PA8 */ - {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D23/PA9 */ - {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D24/PA10 */ - {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D25/PB9 */ - - /* Bottom header */ - /* FIXME (?) What about D48--D50 also being TIMER2_CH[234]? */ - - {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D26/PD2 */ - {GPIOD, 3, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D27/PD3 */ - {GPIOD, 6, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D28/PD6 */ - {GPIOG, 11, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D29/PG11 */ - {GPIOG, 12, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D30/PG12 */ - {GPIOG, 13, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D31/PG13 */ - {GPIOG, 14, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D32/PG14 */ - {GPIOG, 8, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D33/PG8 */ - {GPIOG, 7, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D34/PG7 */ - {GPIOG, 6, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D35/PG6 */ - {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D36/PB5 */ - {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D37/PB6 */ - {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D38/PB7 */ - {GPIOF, 6, 4, NULL, 0, AFIO_EXTI_PF}, /* D39/PF6 */ - {GPIOF, 7, 5, NULL, 0, AFIO_EXTI_PF}, /* D40/PF7 */ - {GPIOF, 8, 6, NULL, 0, AFIO_EXTI_PF}, /* D41/PF8 */ - {GPIOF, 9, 7, NULL, 0, AFIO_EXTI_PF}, /* D42/PF9 */ - {GPIOF, 10, 8, NULL, 0, AFIO_EXTI_PF}, /* D43/PF10 */ - {GPIOF, 11, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D44/PF11 */ - {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D45/PB1 */ - {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D46/PB0 */ - {GPIOA, 0, 0, TIMER5, 1, AFIO_EXTI_PA}, /* D47/PA0 */ - {GPIOA, 1, 1, TIMER5, 2, AFIO_EXTI_PA}, /* D48/PA1 */ - {GPIOA, 2, 2, TIMER5, 3, AFIO_EXTI_PA}, /* D49/PA2 */ - {GPIOA, 3, 3, TIMER5, 4, AFIO_EXTI_PA}, /* D50/PA3 */ - {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D51/PA4 */ - {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D52/PA5 */ - {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D53/PA6 */ - {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D54/PA7 */ - - /* Right (triple) header */ - - {GPIOF, 0, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D55/PF0 */ - {GPIOD, 11, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D56/PD11 */ - {GPIOD, 14, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D57/PD14 */ - {GPIOF, 1, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D58/PF1 */ - {GPIOD, 12, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D59/PD12 */ - {GPIOD, 15, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D60/PD15 */ - {GPIOF, 2, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D61/PF2 */ - {GPIOD, 13, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D62/PD13 */ - {GPIOD, 0, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D63/PD0 */ - {GPIOF, 3, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D64/PF3 */ - {GPIOE, 3, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D65/PE3 */ - {GPIOD, 1, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D66/PD1 */ - {GPIOF, 4, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D67/PF4 */ - {GPIOE, 4, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D68/PE4 */ - {GPIOE, 7, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D69/PE7 */ - {GPIOF, 5, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D70/PF5 */ - {GPIOE, 5, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D71/PE5 */ - {GPIOE, 8, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D72/PE8 */ - {GPIOF, 12, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D73/PF12 */ - {GPIOE, 6, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D74/PE6 */ - {GPIOE, 9, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D75/PE9 */ - {GPIOF, 13, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D76/PF13 */ - {GPIOE, 10, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D77/PE10 */ - {GPIOF, 14, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D78/PF14 */ - {GPIOG, 9, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D79/PG9 */ - {GPIOE, 11, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D80/PE11 */ - {GPIOF, 15, ADCx, NULL, 0, AFIO_EXTI_PF}, /* D81/PF15 */ - {GPIOG, 10, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D82/PG10 */ - {GPIOE, 12, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D83/PE12 */ - {GPIOG, 0, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D84/PG0 */ - {GPIOD, 5, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D85/PD5 */ - {GPIOE, 13, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D86/PE13 */ - {GPIOG, 1, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D87/PG1 */ - {GPIOD, 4, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D88/PD4 */ - {GPIOE, 14, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D89/PE14 */ - {GPIOG, 2, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D90/PG2 */ - {GPIOE, 1, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D91/PE1 */ - {GPIOE, 15, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D92/PE15 */ - {GPIOG, 3, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D93/PG3 */ - {GPIOE, 0, ADCx, NULL, 0, AFIO_EXTI_PE}, /* D94/PE0 */ - {GPIOD, 8, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D95/PD8 */ - {GPIOG, 4, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D96/PG4 */ - {GPIOD, 9, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D97/PD9 */ - {GPIOG, 5, ADCx, NULL, 0, AFIO_EXTI_PG}, /* D98/PG5 */ - {GPIOD, 10, ADCx, NULL, 0, AFIO_EXTI_PD} /* D99/PD10 */ -}; - -#elif defined(BOARD_maple_mini) - -PinMapping PIN_MAP[NR_GPIO_PINS] = { - /* Top header */ - - {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D0/PB11 */ - {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D1/PB10 */ - {GPIOB, 2, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D2/PB2 */ - {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D3/PB0 */ - {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D4/PA7 */ - {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D5/PA6 */ - {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D6/PA5 */ - {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D7/PA4 */ - {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D8/PA3 */ - {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D9/PA2 */ - {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D10/PA1 */ - {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D11/PA0 */ - {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D12/PC15 */ - {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D13/PC14 */ - {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D14/PC13 */ - - /* Bottom header */ - - {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D15/PB7 */ - {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D16/PB6 */ - {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D17/PB5 */ - {GPIOB, 4, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D18/PB4 */ - {GPIOB, 3, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D19/PB3 */ - {GPIOA, 15, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D20/PA15 */ - {GPIOA, 14, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D21/PA14 */ - {GPIOA, 13, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D22/PA13 */ - {GPIOA, 12, ADCx, NULL, 0, AFIO_EXTI_PA}, /* D23/PA12 */ - {GPIOA, 11, ADCx, TIMER1, 4, AFIO_EXTI_PA}, /* D24/PA11 */ - {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D25/PA10 */ - {GPIOA, 9, ADCx, TIMER2, 2, AFIO_EXTI_PA}, /* D26/PA9 */ - {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D27/PA8 */ - {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D28/PB15 */ - {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB14 */ - {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB13 */ - {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ - {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D32/PB8 */ - {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D33/PB1 */ -}; - -#elif defined(BOARD_maple_RET6) - -PinMapping PIN_MAP[NR_GPIO_PINS] = { - {GPIOA, 3, 3, TIMER2, 4, AFIO_EXTI_PA}, /* D0/PA3 */ - {GPIOA, 2, 2, TIMER2, 3, AFIO_EXTI_PA}, /* D1/PA2 */ - {GPIOA, 0, 0, TIMER2, 1, AFIO_EXTI_PA}, /* D2/PA0 */ - {GPIOA, 1, 1, TIMER2, 2, AFIO_EXTI_PA}, /* D3/PA1 */ - {GPIOB, 5, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D4/PB5 */ - {GPIOB, 6, ADCx, TIMER4, 1, AFIO_EXTI_PB}, /* D5/PB6 */ - {GPIOA, 8, ADCx, TIMER1, 1, AFIO_EXTI_PA}, /* D6/PA8 */ - {GPIOA, 9, ADCx, TIMER1, 2, AFIO_EXTI_PA}, /* D7/PA9 */ - {GPIOA, 10, ADCx, TIMER1, 3, AFIO_EXTI_PA}, /* D8/PA10 */ - {GPIOB, 7, ADCx, TIMER4, 2, AFIO_EXTI_PB}, /* D9/PB7 */ - {GPIOA, 4, 4, NULL, 0, AFIO_EXTI_PA}, /* D10/PA4 */ - {GPIOA, 7, 7, TIMER3, 2, AFIO_EXTI_PA}, /* D11/PA7 */ - {GPIOA, 6, 6, TIMER3, 1, AFIO_EXTI_PA}, /* D12/PA6 */ - {GPIOA, 5, 5, NULL, 0, AFIO_EXTI_PA}, /* D13/PA5 (LED) */ - {GPIOB, 8, ADCx, TIMER4, 3, AFIO_EXTI_PB}, /* D14/PB8 */ - - /* Little header */ - - {GPIOC, 0, 10, NULL, 0, AFIO_EXTI_PC}, /* D15/PC0 */ - {GPIOC, 1, 11, NULL, 0, AFIO_EXTI_PC}, /* D16/PC1 */ - {GPIOC, 2, 12, NULL, 0, AFIO_EXTI_PC}, /* D17/PC2 */ - {GPIOC, 3, 13, NULL, 0, AFIO_EXTI_PC}, /* D18/PC3 */ - {GPIOC, 4, 14, NULL, 0, AFIO_EXTI_PC}, /* D19/PC4 */ - {GPIOC, 5, 15, NULL, 0, AFIO_EXTI_PC}, /* D20/PC5 */ - - /* External header */ - - {GPIOC, 13, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D21/PC13 */ - {GPIOC, 14, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D22/PC14 */ - {GPIOC, 15, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D23/PC15 */ - {GPIOB, 9, ADCx, TIMER4, 4, AFIO_EXTI_PB}, /* D24/PB9 */ - {GPIOD, 2, ADCx, NULL, 0, AFIO_EXTI_PD}, /* D25/PD2 */ - {GPIOC, 10, ADCx, NULL, 0, AFIO_EXTI_PC}, /* D26/PC10 */ - {GPIOB, 0, 8, TIMER3, 3, AFIO_EXTI_PB}, /* D27/PB0 */ - {GPIOB, 1, 9, TIMER3, 4, AFIO_EXTI_PB}, /* D28/PB1 */ - {GPIOB, 10, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D29/PB10 */ - {GPIOB, 11, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D30/PB11 */ - {GPIOB, 12, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D31/PB12 */ - {GPIOB, 13, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D32/PB13 */ - {GPIOB, 14, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D33/PB14 */ - {GPIOB, 15, ADCx, NULL, 0, AFIO_EXTI_PB}, /* D34/PB15 */ - {GPIOC, 6, ADCx, TIMER8, 1, AFIO_EXTI_PC}, /* D35/PC6 */ - {GPIOC, 7, ADCx, TIMER8, 2, AFIO_EXTI_PC}, /* D36/PC7 */ - {GPIOC, 8, ADCx, TIMER8, 3, AFIO_EXTI_PC}, /* D37/PC8 */ - {GPIOC, 9, ADCx, TIMER8, 4, AFIO_EXTI_PC} /* D38/PC9 (BUT) */ -}; - -#else - -#error "Board type has not been selected correctly." - -#endif diff --git a/wirish/boards.h b/wirish/boards.h index d186dc4..b72609d 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -3,29 +3,37 @@ * * Copyright (c) 2010 Bryan Newbold. * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. *****************************************************************************/ -/* This file contains board-specific pin mapping tables. To add a new board - * type, copy the "BOARD_maple" section below and edit it as needed, then - * update your build toolchain with a new "BOARD" type. This must match the - * separate MCU type (which determines the ../libmaple configuration). +/** + * @file boards.h + * @author Bryan Newbold , + * Marti Bolivar + * @brief Board-specific pin information. + * + * To add a new board type, add a new pair of files to + * /wirish/boards/, update the section below with a new "BOARD" type, + * and update /wirish/rules.mk to include your boards/your_board.cpp + * file in the top-level Makefile build. */ #ifndef _BOARDS_H_ @@ -34,12 +42,13 @@ #include "libmaple.h" #include "gpio.h" #include "timer.h" -#include "native_sram.h" + +#include "wirish_types.h" /* Set of all possible pin names; not all boards have all these (note - that we use the Dx convention since all of the Maple's pins are - "digital" pins (e.g. can be used with digitalRead() and - digitalWrite()), but not all of them are connected to ADCs. */ + * that we use the Dx convention since all of the Maple's pins are + * "digital" pins (e.g. can be used with digitalRead() and + * digitalWrite()), but not all of them are connected to ADCs. */ enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, D10, D11, D12, D13, D14, D15, D16, D17, D18, D19, D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, @@ -50,89 +59,30 @@ enum { D92, D93, D94, D95, D96, D97, D98, D99, D100, D101, D102, D103, D104, D105, D106, D107, D108, D109, D110, D111, }; -#define ADC_INVALID 0xFFFFFFFF - -/* Pin mapping: pin number -> STM32 info */ -typedef struct PinMapping { - gpio_dev *gpio_device; - uint32 pin; - uint32 adc_channel; - timer_dev* timer_device; - uint8 timer_chan; - afio_exti_port ext_port; -} PinMapping; +/** + * @brief Maps each pin to a corresponding struct stm32_pin_info. + * @see struct stm32_pin_info + */ +extern stm32_pin_info PIN_MAP[]; -/* Maps every digital pin to a PinMapping */ -extern PinMapping PIN_MAP[]; +/** Board-specific initialization function. */ +extern void boardInit(void); -/* LeafLabs Maple rev3, rev5 */ #ifdef BOARD_maple - - #define CYCLES_PER_MICROSECOND 72 - #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - - #define BOARD_BUTTON_PIN 38 - #define BOARD_LED_PIN 13 - - /* Total number of GPIO pins that are broken out to headers and - intended for general use. */ - #define NR_GPIO_PINS 39 - - #define BOARD_INIT do { \ - } while(0) - +#include "boards/maple.h" #elif defined(BOARD_maple_native) - - /* LeafLabs Maple Native (prototype) */ - - #define CYCLES_PER_MICROSECOND 72 - #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - - #define BOARD_LED_PIN D21 - #define BOARD_BUTTON_PIN D18 - - #define NR_GPIO_PINS 100 - - #define BOARD_INIT do { \ - initNativeSRAM(); - } while(0) - +#include "boards/maple_native.h" #elif defined(BOARD_maple_mini) - - #define CYCLES_PER_MICROSECOND 72 - #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - - #define BOARD_BUTTON_PIN 32 - #define BOARD_LED_PIN 33 - - #define NR_GPIO_PINS 34 - - /* Since we want the Serial Wire/JTAG pins as GPIOs, disable both - * SW and JTAG debug support */ - #define BOARD_INIT \ - do { \ - afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); \ - } while (0) - +#include "boards/maple_mini.h" #elif defined(BOARD_maple_RET6) - - #define CYCLES_PER_MICROSECOND 72 - #define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ - - #define BOARD_BUTTON_PIN 38 - #define BOARD_LED_PIN 13 - - /* Total number of GPIO pins that are broken out to headers and - intended for general use. */ - #define NR_GPIO_PINS 39 - - #define BOARD_INIT do { \ - } while(0) - +/* + * **NOT** MAPLE REV6. This the **Maple RET6 EDITION**, which is a + * Maple with an STM32F103RET6 (...RET6) instead of an STM32F103RBT6 + * (...RBT6) on it. Maple Rev6 (as of March 2011) DOES NOT EXIST. + */ +#include "boards/maple_RET6.h" #else - #error "Board type has not been selected correctly." - #endif #endif diff --git a/wirish/boards/maple.cpp b/wirish/boards/maple.cpp new file mode 100644 index 0000000..cebd222 --- /dev/null +++ b/wirish/boards/maple.cpp @@ -0,0 +1,94 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple.cpp + * @author Marti Bolivar + * @brief Maple PIN_MAP and boardInit(). + */ + +#include "gpio.h" +#include "timer.h" + +#include "maple.h" + +#ifdef BOARD_maple + +void boardInit(void) { +} + +stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { + + /* Top header */ + + {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + + /* Little header */ + + {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + + /* External header */ + + {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, NULL, 6, 0, ADCx}, /* D35/PC6 */ + {GPIOC, NULL, 7, 0, ADCx}, /* D36/PC7 */ + {GPIOC, NULL, 8, 0, ADCx}, /* D37/PC8 */ + {GPIOC, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ +}; + +#endif diff --git a/wirish/boards/maple.h b/wirish/boards/maple.h new file mode 100644 index 0000000..519698b --- /dev/null +++ b/wirish/boards/maple.h @@ -0,0 +1,59 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple.h + * @author Marti Bolivar + * @brief Private include file for Maple in boards.h + */ + +#include "wirish_types.h" + +#ifndef _BOARD_MAPLE_H_ +#define _BOARD_MAPLE_H_ + +#define CYCLES_PER_MICROSECOND 72 +#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ + +#define BOARD_BUTTON_PIN 38 +#define BOARD_LED_PIN 13 + +/* Number of USARTs/UARTs whose pins are broken out to headers */ +#define NR_USARTS 3 + +/* Default USART pin numbers (not considering AFIO remap) */ +#define BOARD_USART1_TX_PIN 7 +#define BOARD_USART1_RX_PIN 8 +#define BOARD_USART2_TX_PIN 1 +#define BOARD_USART2_RX_PIN 0 +#define BOARD_USART3_TX_PIN 29 +#define BOARD_USART3_RX_PIN 30 + +/* Total number of GPIO pins that are broken out to headers and + intended for general use. */ +#define NR_GPIO_PINS 39 + +#endif diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6.cpp new file mode 100644 index 0000000..ae31ce3 --- /dev/null +++ b/wirish/boards/maple_RET6.cpp @@ -0,0 +1,88 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_RET6.cpp + * @author Marti Bolivar + * @brief Maple RET6 Edition PIN_MAP and boardInit() + */ + +#include "maple_RET6.h" + +#ifdef BOARD_maple_RET6 + +void boardInit(void) { +} + +stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { + {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + + /* Little header */ + + {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + + /* External header */ + + {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, TIMER8, 6, 1, ADCx}, /* D35/PC6 */ + {GPIOC, TIMER8, 7, 2, ADCx}, /* D36/PC7 */ + {GPIOC, TIMER8, 8, 3, ADCx}, /* D37/PC8 */ + {GPIOC, TIMER8, 9, 4, ADCx} /* D38/PC9 (BUT) */ +}; + +#endif diff --git a/wirish/boards/maple_RET6.h b/wirish/boards/maple_RET6.h new file mode 100644 index 0000000..63510c0 --- /dev/null +++ b/wirish/boards/maple_RET6.h @@ -0,0 +1,61 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_RET6.h + * @author Marti Bolivar + * @brief Private include file for Maple RET6 Edition in boards.h + * + * See maple.h for more information on these definitions. + */ + +#include "gpio.h" +#include "timer.h" + +#include "wirish_types.h" + +#ifndef _BOARDS_MAPLE_RET6_H_ +#define _BOARDS_MAPLE_RET6_H_ + +#define CYCLES_PER_MICROSECOND 72 +#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ + +#define BOARD_BUTTON_PIN 38 +#define BOARD_LED_PIN 13 + +/* Note: UART4 and UART5 have pins which aren't broken out :( */ +#define NR_USARTS 3 + +#define BOARD_USART1_TX_PIN 7 +#define BOARD_USART1_RX_PIN 8 +#define BOARD_USART2_TX_PIN 1 +#define BOARD_USART2_RX_PIN 0 +#define BOARD_USART3_TX_PIN 29 +#define BOARD_USART3_RX_PIN 30 + +#define NR_GPIO_PINS 39 + +#endif diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp new file mode 100644 index 0000000..8c005cf --- /dev/null +++ b/wirish/boards/maple_mini.cpp @@ -0,0 +1,87 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_mini.cpp + * @author Marti Bolivar + * @brief Maple Mini PIN_MAP and boardInit(). + */ + +#include "maple_mini.h" +#include "gpio.h" + +#ifdef BOARD_maple_mini + +/* Since we want the Serial Wire/JTAG pins as GPIOs, disable both SW + * and JTAG debug support */ +void boardInit(void) { + afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); +} + +stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { + + /* Top header */ + + {GPIOB, NULL, 11, 0, ADCx}, /* D0/PB11 */ + {GPIOB, NULL, 10, 0, ADCx}, /* D1/PB10 */ + {GPIOB, NULL, 2, 0, ADCx}, /* D2/PB2 */ + {GPIOB, TIMER3, 0, 3, 8}, /* D3/PB0 */ + {GPIOA, TIMER3, 7, 2, 7}, /* D4/PA7 */ + {GPIOA, TIMER3, 6, 1, 6}, /* D5/PA6 */ + {GPIOA, NULL, 5, 0, 5}, /* D6/PA5 */ + {GPIOA, NULL, 4, 0, 4}, /* D7/PA4 */ + {GPIOA, TIMER2, 3, 4, 3}, /* D8/PA3 */ + {GPIOA, TIMER2, 2, 3, 2}, /* D9/PA2 */ + {GPIOA, TIMER2, 1, 2, 1}, /* D10/PA1 */ + {GPIOA, TIMER2, 0, 1, 0}, /* D11/PA0 */ + {GPIOC, NULL, 15, 0, ADCx}, /* D12/PC15 */ + {GPIOC, NULL, 14, 0, ADCx}, /* D13/PC14 */ + {GPIOC, NULL, 13, 0, ADCx}, /* D14/PC13 */ + + /* Bottom header */ + + {GPIOB, TIMER4, 7, 2, ADCx}, /* D15/PB7 */ + {GPIOB, TIMER4, 6, 1, ADCx}, /* D16/PB6 */ + {GPIOB, NULL, 5, 0, ADCx}, /* D17/PB5 */ + {GPIOB, NULL, 4, 0, ADCx}, /* D18/PB4 */ + {GPIOB, NULL, 3, 0, ADCx}, /* D19/PB3 */ + {GPIOA, NULL, 15, 0, ADCx}, /* D20/PA15 */ + {GPIOA, NULL, 14, 0, ADCx}, /* D21/PA14 */ + {GPIOA, NULL, 13, 0, ADCx}, /* D22/PA13 */ + {GPIOA, NULL, 12, 0, ADCx}, /* D23/PA12 */ + {GPIOA, TIMER1, 11, 4, ADCx}, /* D24/PA11 */ + {GPIOA, TIMER1, 10, 3, ADCx}, /* D25/PA10 */ + {GPIOA, TIMER2, 9, 2, ADCx}, /* D26/PA9 */ + {GPIOA, TIMER1, 8, 1, ADCx}, /* D27/PA8 */ + {GPIOB, NULL, 15, 0, ADCx}, /* D28/PB15 */ + {GPIOB, NULL, 14, 0, ADCx}, /* D29/PB14 */ + {GPIOB, NULL, 13, 0, ADCx}, /* D30/PB13 */ + {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, TIMER4, 8, 3, ADCx}, /* D32/PB8 */ + {GPIOB, TIMER3, 1, 4, 9}, /* D33/PB1 */ +}; + +#endif diff --git a/wirish/boards/maple_mini.h b/wirish/boards/maple_mini.h new file mode 100644 index 0000000..bfb92a5 --- /dev/null +++ b/wirish/boards/maple_mini.h @@ -0,0 +1,60 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_mini.h + * @author Marti Bolivar + * @brief Private include file for Maple Mini in boards.h + * + * See maple.h for more information on these definitions. + */ + +#include "gpio.h" +#include "timer.h" + +#include "wirish_types.h" + +#ifndef _BOARD_MAPLE_MINI_H_ +#define _BOARD_MAPLE_MINI_H_ + +#define CYCLES_PER_MICROSECOND 72 +#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */ + +#define BOARD_BUTTON_PIN 32 +#define BOARD_LED_PIN 33 + +#define NR_USARTS 3 + +#define BOARD_USART1_TX_PIN 26 +#define BOARD_USART1_RX_PIN 25 +#define BOARD_USART2_TX_PIN 9 +#define BOARD_USART2_RX_PIN 8 +#define BOARD_USART3_TX_PIN 1 +#define BOARD_USART3_RX_PIN 0 + +#define NR_GPIO_PINS 34 + +#endif diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp new file mode 100644 index 0000000..c04e98f --- /dev/null +++ b/wirish/boards/maple_native.cpp @@ -0,0 +1,155 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_native.cpp + * @author Marti Bolivar + * @brief Maple Native PIN_MAP and boardInit(). + */ + +#include "maple_native.h" +#include "native_sram.h" + +#ifdef BOARD_maple_native + +void boardInit(void) { + initNativeSRAM(); +} + +stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { + + /* Top header */ + + {GPIOB, NULL, 10, 0, ADCx}, /* D0/PB10 */ + {GPIOB, NULL, 2, 0, ADCx}, /* D1/PB2 */ + {GPIOB, NULL, 12, 0, ADCx}, /* D2/PB12 */ + {GPIOB, NULL, 13, 0, ADCx}, /* D3/PB13 */ + {GPIOB, NULL, 14, 0, ADCx}, /* D4/PB14 */ + {GPIOB, NULL, 15, 0, ADCx}, /* D5/PB15 */ + {GPIOC, NULL, 0, 0, 10}, /* D6/PC0 */ + {GPIOC, NULL, 1, 0, 11}, /* D7/PC1 */ + {GPIOC, NULL, 2, 0, 12}, /* D8/PC2 */ + {GPIOC, NULL, 3, 0, 13}, /* D9/PC3 */ + {GPIOC, NULL, 4, 0, 14}, /* D10/PC4 */ + {GPIOC, NULL, 5, 0, 15}, /* D11/PC5 */ + {GPIOC, TIMER8, 6, 1, ADCx}, /* D12/PC6 */ + {GPIOC, TIMER8, 7, 2, ADCx}, /* D13/PC7 */ + {GPIOC, TIMER8, 8, 3, ADCx}, /* D14/PC8 */ + {GPIOC, TIMER8, 9, 4, ADCx}, /* D15/PC9 */ + {GPIOC, NULL, 10, 0, ADCx}, /* D16/PC10 */ + {GPIOC, NULL, 11, 0, ADCx}, /* D17/PC11 */ + {GPIOC, NULL, 12, 0, ADCx}, /* D18/PC12 */ + {GPIOC, NULL, 13, 0, ADCx}, /* D19/PC13 */ + {GPIOC, NULL, 14, 0, ADCx}, /* D20/PC14 */ + {GPIOC, NULL, 15, 0, ADCx}, /* D21/PC15 */ + {GPIOA, TIMER1, 8, 1, ADCx}, /* D22/PA8 */ + {GPIOA, TIMER1, 9, 2, ADCx}, /* D23/PA9 */ + {GPIOA, TIMER1, 10, 3, ADCx}, /* D24/PA10 */ + {GPIOB, TIMER4, 9, 4, ADCx}, /* D25/PB9 */ + + /* Bottom header */ + /* FIXME (?) What about D48--D50 also being TIMER2_CH[234]? */ + + {GPIOD, NULL, 2, 0, ADCx}, /* D26/PD2 */ + {GPIOD, NULL, 3, 0, ADCx}, /* D27/PD3 */ + {GPIOD, NULL, 6, 0, ADCx}, /* D28/PD6 */ + {GPIOG, NULL, 11, 0, ADCx}, /* D29/PG11 */ + {GPIOG, NULL, 12, 0, ADCx}, /* D30/PG12 */ + {GPIOG, NULL, 13, 0, ADCx}, /* D31/PG13 */ + {GPIOG, NULL, 14, 0, ADCx}, /* D32/PG14 */ + {GPIOG, NULL, 8, 0, ADCx}, /* D33/PG8 */ + {GPIOG, NULL, 7, 0, ADCx}, /* D34/PG7 */ + {GPIOG, NULL, 6, 0, ADCx}, /* D35/PG6 */ + {GPIOB, NULL, 5, 0, ADCx}, /* D36/PB5 */ + {GPIOB, TIMER4, 6, 1, ADCx}, /* D37/PB6 */ + {GPIOB, TIMER4, 7, 2, ADCx}, /* D38/PB7 */ + {GPIOF, NULL, 6, 0, 4}, /* D39/PF6 */ + {GPIOF, NULL, 7, 0, 5}, /* D40/PF7 */ + {GPIOF, NULL, 8, 0, 6}, /* D41/PF8 */ + {GPIOF, NULL, 9, 0, 7}, /* D42/PF9 */ + {GPIOF, NULL, 10, 0, 8}, /* D43/PF10 */ + {GPIOF, NULL, 11, 0, ADCx}, /* D44/PF11 */ + {GPIOB, TIMER3, 1, 4, 9}, /* D45/PB1 */ + {GPIOB, TIMER3, 0, 3, 8}, /* D46/PB0 */ + {GPIOA, TIMER5, 0, 1, 0}, /* D47/PA0 */ + {GPIOA, TIMER5, 1, 2, 1}, /* D48/PA1 */ + {GPIOA, TIMER5, 2, 3, 2}, /* D49/PA2 */ + {GPIOA, TIMER5, 3, 4, 3}, /* D50/PA3 */ + {GPIOA, NULL, 4, 0, 4}, /* D51/PA4 */ + {GPIOA, NULL, 5, 0, 5}, /* D52/PA5 */ + {GPIOA, TIMER3, 6, 1, 6}, /* D53/PA6 */ + {GPIOA, TIMER3, 7, 2, 7}, /* D54/PA7 */ + + /* Right (triple) header */ + + {GPIOF, NULL, 0, 0, ADCx}, /* D55/PF0 */ + {GPIOD, NULL, 11, 0, ADCx}, /* D56/PD11 */ + {GPIOD, NULL, 14, 0, ADCx}, /* D57/PD14 */ + {GPIOF, NULL, 1, 0, ADCx}, /* D58/PF1 */ + {GPIOD, NULL, 12, 0, ADCx}, /* D59/PD12 */ + {GPIOD, NULL, 15, 0, ADCx}, /* D60/PD15 */ + {GPIOF, NULL, 2, 0, ADCx}, /* D61/PF2 */ + {GPIOD, NULL, 13, 0, ADCx}, /* D62/PD13 */ + {GPIOD, NULL, 0, 0, ADCx}, /* D63/PD0 */ + {GPIOF, NULL, 3, 0, ADCx}, /* D64/PF3 */ + {GPIOE, NULL, 3, 0, ADCx}, /* D65/PE3 */ + {GPIOD, NULL, 1, 0, ADCx}, /* D66/PD1 */ + {GPIOF, NULL, 4, 0, ADCx}, /* D67/PF4 */ + {GPIOE, NULL, 4, 0, ADCx}, /* D68/PE4 */ + {GPIOE, NULL, 7, 0, ADCx}, /* D69/PE7 */ + {GPIOF, NULL, 5, 0, ADCx}, /* D70/PF5 */ + {GPIOE, NULL, 5, 0, ADCx}, /* D71/PE5 */ + {GPIOE, NULL, 8, 0, ADCx}, /* D72/PE8 */ + {GPIOF, NULL, 12, 0, ADCx}, /* D73/PF12 */ + {GPIOE, NULL, 6, 0, ADCx}, /* D74/PE6 */ + {GPIOE, NULL, 9, 0, ADCx}, /* D75/PE9 */ + {GPIOF, NULL, 13, 0, ADCx}, /* D76/PF13 */ + {GPIOE, NULL, 10, 0, ADCx}, /* D77/PE10 */ + {GPIOF, NULL, 14, 0, ADCx}, /* D78/PF14 */ + {GPIOG, NULL, 9, 0, ADCx}, /* D79/PG9 */ + {GPIOE, NULL, 11, 0, ADCx}, /* D80/PE11 */ + {GPIOF, NULL, 15, 0, ADCx}, /* D81/PF15 */ + {GPIOG, NULL, 10, 0, ADCx}, /* D82/PG10 */ + {GPIOE, NULL, 12, 0, ADCx}, /* D83/PE12 */ + {GPIOG, NULL, 0, 0, ADCx}, /* D84/PG0 */ + {GPIOD, NULL, 5, 0, ADCx}, /* D85/PD5 */ + {GPIOE, NULL, 13, 0, ADCx}, /* D86/PE13 */ + {GPIOG, NULL, 1, 0, ADCx}, /* D87/PG1 */ + {GPIOD, NULL, 4, 0, ADCx}, /* D88/PD4 */ + {GPIOE, NULL, 14, 0, ADCx}, /* D89/PE14 */ + {GPIOG, NULL, 2, 0, ADCx}, /* D90/PG2 */ + {GPIOE, NULL, 1, 0, ADCx}, /* D91/PE1 */ + {GPIOE, NULL, 15, 0, ADCx}, /* D92/PE15 */ + {GPIOG, NULL, 3, 0, ADCx}, /* D93/PG3 */ + {GPIOE, NULL, 0, 0, ADCx}, /* D94/PE0 */ + {GPIOD, NULL, 8, 0, ADCx}, /* D95/PD8 */ + {GPIOG, NULL, 4, 0, ADCx}, /* D96/PG4 */ + {GPIOD, NULL, 9, 0, ADCx}, /* D97/PD9 */ + {GPIOG, NULL, 5, 0, ADCx}, /* D98/PG5 */ + {GPIOD, NULL, 10, 0, ADCx} /* D99/PD10 */ +}; + +#endif diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h new file mode 100644 index 0000000..21fc480 --- /dev/null +++ b/wirish/boards/maple_native.h @@ -0,0 +1,64 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file maple_native.h + * @author Marti Bolivar + * @brief Private include file for Maple Native in boards.h + * + * See maple.h for more information on these definitions. + */ + +#include "gpio.h" +#include "timer.h" + +#include "wirish_types.h" + +#ifndef _BOARD_MAPLE_NATIVE_H_ +#define _BOARD_MAPLE_NATIVE_H_ + +#define CYCLES_PER_MICROSECOND 72 +#define SYSTICK_RELOAD_VAL 71999 + +#define BOARD_LED_PIN D21 +#define BOARD_BUTTON_PIN D18 + +#define NR_USARTS 5 + +#define BOARD_USART1_TX_PIN 25 +#define BOARD_USART1_RX_PIN 26 +#define BOARD_USART2_TX_PIN 51 +#define BOARD_USART2_RX_PIN 52 +#define BOARD_USART3_TX_PIN 0 +#define BOARD_USART3_RX_PIN 1 +#define BOARD_UART4_TX_PIN 18 +#define BOARD_UART4_RX_PIN 19 +#define BOARD_UART5_TX_PIN 20 +#define BOARD_UART5_RX_PIN 28 + +#define NR_GPIO_PINS 100 + +#endif diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp index 5b32b05..060994f 100644 --- a/wirish/ext_interrupts.cpp +++ b/wirish/ext_interrupts.cpp @@ -49,8 +49,8 @@ void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { exti_trigger_mode outMode = exti_out_mode(mode); - exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].pin), - PIN_MAP[pin].ext_port, + exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin), + gpio_exti_port(PIN_MAP[pin].gpio_device), handler, outMode); } @@ -64,7 +64,7 @@ void detachInterrupt(uint8 pin) { return; } - exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].pin)); + exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin)); } static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) { diff --git a/wirish/rules.mk b/wirish/rules.mk index d250cb9..c1d59bc 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -4,8 +4,9 @@ dirstack_$(sp) := $(d) d := $(dir) BUILDDIRS += $(BUILD_PATH)/$(d) BUILDDIRS += $(BUILD_PATH)/$(d)/comm +BUILDDIRS += $(BUILD_PATH)/$(d)/boards -WIRISH_INCLUDES := -I$(d) -I$(d)/comm +WIRISH_INCLUDES := -I$(d) -I$(d)/comm -I$(d)/boards # Local flags CFLAGS_$(d) := $(WIRISH_INCLUDES) $(LIBMAPLE_INCLUDES) @@ -15,6 +16,10 @@ cSRCS_$(d) := cppSRCS_$(d) := wirish_math.cpp \ Print.cpp \ + boards/maple.cpp \ + boards/maple_mini.cpp \ + boards/maple_native.cpp \ + boards/maple_RET6.cpp \ comm/HardwareSerial.cpp \ comm/HardwareSPI.cpp \ usb_serial.cpp \ @@ -27,9 +32,8 @@ cppSRCS_$(d) := wirish_math.cpp \ ext_interrupts.cpp \ wirish_digital.cpp \ native_sram.cpp \ - boards.cpp -cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) +cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%) OBJS_$(d) := $(cFILES_$(d):%.c=$(BUILD_PATH)/%.o) \ diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp index 6dcb1b5..aeed089 100644 --- a/wirish/wirish.cpp +++ b/wirish/wirish.cpp @@ -59,8 +59,7 @@ void init(void) { setupADC(); setupTimers(); setupUSB(); - - BOARD_INIT; + boardInit(); } static void setupFlash(void) { diff --git a/wirish/wirish.h b/wirish/wirish.h index 319df97..13b14b6 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -33,6 +33,7 @@ #include "libmaple.h" +#include "wirish_types.h" #include "boards.h" #include "io.h" #include "bits.h" diff --git a/wirish/wirish_analog.cpp b/wirish/wirish_analog.cpp index a658184..9e99aa5 100644 --- a/wirish/wirish_analog.cpp +++ b/wirish/wirish_analog.cpp @@ -33,7 +33,7 @@ /* Assumes that the ADC has been initialized and that the pin is set * to ANALOG_INPUT */ uint32 analogRead(uint8 pin) { - if(PIN_MAP[pin].adc_channel == ADC_INVALID) { + if(PIN_MAP[pin].adc_channel == ADCx) { return 0; } diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp index 4b68861..278cf10 100644 --- a/wirish/wirish_digital.cpp +++ b/wirish/wirish_digital.cpp @@ -70,7 +70,7 @@ void pinMode(uint8 pin, WiringPinMode mode) { return; } - gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, outputMode); + gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, outputMode); if (PIN_MAP[pin].timer_device != NULL) { /* enable/disable timer channels if we're switching into or @@ -93,7 +93,7 @@ uint32 digitalRead(uint8 pin) { return 0; } - return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin) ? + return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin) ? HIGH : LOW; } @@ -102,7 +102,7 @@ void digitalWrite(uint8 pin, uint8 val) { return; } - gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, val); + gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, val); } void togglePin(uint8 pin) { @@ -110,7 +110,7 @@ void togglePin(uint8 pin) { return; } - gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin); + gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin); } uint8 isButtonPressed() { diff --git a/wirish/wirish_types.h b/wirish/wirish_types.h new file mode 100644 index 0000000..84591ea --- /dev/null +++ b/wirish/wirish_types.h @@ -0,0 +1,51 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish_types.h + * @author Marti Bolivar + * @brief Wirish library type definitions. + */ + +#include "gpio.h" +#include "timer.h" + +#ifndef _WIRISH_TYPES_H_ +#define _WIRISH_TYPES_H_ + +/** Stores STM32-specific information related to a given pin. */ +typedef struct stm32_pin_info { + gpio_dev *gpio_device; /**< Maple pin's GPIO device */ + timer_dev *timer_device; /**< Maple pin's timer device, or NULL if none. */ + uint8 gpio_pin; /**< GPIO pin */ + uint8 timer_chan; /**< Timer channel, or 0 if none. */ + uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ +} stm32_pin_info; + +/** Invalid adc_channel value */ +#define ADCx 0xFF + +#endif -- cgit v1.2.3 From f8081eeb04c9cb511adaf58e201c7cfbe1ddfbd4 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 25 Mar 2011 20:09:30 -0400 Subject: Final stm32_pin_info design candidate; ADC3 support on Native. Added an adc_dev to struct stm32_pin_info. This was necessary to add support for the channels on the Native which are only connected to ADC3, but it does add a bunch of NULLs to the PIN_MAPs. I don't think any other peripherals need representation on a per-pin basis. Each peripheral library will be responsible for keeping track of related GPIO ports and bits, and we can throw #defines in to boards/*.h for other things (e.g. BOARD_SPI1_MISO_PIN). Fleshed out the ADC refactor and brought it more in keeping with the new design as it evolves. A couple of other tweaks. Notably: waitForButtonPress() now takes a default argument meaning "wait forever". Removed Maple-specific documentation from core functions in io.h; this information will need to go into the individual board docs files. --- examples/test-session.cpp | 50 ++++--- libmaple/adc.c | 65 ++++++--- libmaple/adc.h | 294 +++++++++++++++++++++++++++++---------- libmaple/timer.c | 4 +- notes/coding_standard.txt | 44 ++++++ notes/native-pin-definitions.txt | 201 -------------------------- notes/pin-definitions.txt | 201 ++++++++++++++++++++++++++ wirish/boards.cpp | 145 +++++++++++++++++++ wirish/boards.h | 16 ++- wirish/boards/maple.cpp | 78 +++++------ wirish/boards/maple_RET6.cpp | 81 +++++------ wirish/boards/maple_mini.cpp | 68 ++++----- wirish/boards/maple_native.cpp | 202 +++++++++++++-------------- wirish/ext_interrupts.cpp | 4 +- wirish/io.h | 33 ++--- wirish/pwm.cpp | 2 +- wirish/rules.mk | 4 +- wirish/wirish.cpp | 128 ----------------- wirish/wirish.h | 2 - wirish/wirish_analog.cpp | 9 +- wirish/wirish_digital.cpp | 28 ++-- wirish/wirish_types.h | 26 ++-- 22 files changed, 967 insertions(+), 718 deletions(-) delete mode 100644 notes/native-pin-definitions.txt create mode 100644 notes/pin-definitions.txt create mode 100644 wirish/boards.cpp delete mode 100644 wirish/wirish.cpp (limited to 'wirish') diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 28c02f3..110b219 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -27,16 +27,13 @@ const uint8 adc_pins[] = #elif defined(BOARD_maple_mini) const uint8 pwm_pins[] = {3, 4, 5, 8, 9, 10, 11, 15, 16, 25, 26, 27}; -const uint8 adc_pins[] = {3, 4, 5, 6, 7, 8, 9, 10, 11, 33}; // NB: 33 is LED +const uint8 adc_pins[] = {3, 4, 5, 6, 7, 8, 9, 10, 11, 33}; #elif defined(BOARD_maple_native) const uint8 pwm_pins[] = {12, 13, 14, 15, 22, 23, 24, 25, 37, 38, 45, 46, 47, 48, 49, 50, 53, 54}; -const uint8 adc_pins[] = {6, 7, 8, 9, 10, 11, - /* the following are on ADC3, which lacks support: - 39, 40, 41, 42, 43, 45, */ +const uint8 adc_pins[] = {6, 7, 8, 9, 10, 11, 39, 40, 41, 42, 43, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54}; - #else #error "Board type has not been selected correctly" @@ -351,21 +348,34 @@ void cmd_everything(void) { // TODO void fast_gpio(int maple_pin) { gpio_dev *dev = PIN_MAP[maple_pin].gpio_device; - uint32 pin = PIN_MAP[maple_pin].gpio_pin; - - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); - gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0); + uint32 bit = PIN_MAP[maple_pin].gpio_bit; + + gpio_write_bit(dev, bit, 1); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); } void cmd_serial1_serial3(void) { diff --git a/libmaple/adc.c b/libmaple/adc.c index 3d38596..73dce0a 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -59,43 +59,44 @@ adc_dev adc3 = { const adc_dev *ADC3 = &adc3; #endif -static void adc_calibrate(const adc_dev *dev); - /** - * @brief Initialize an ADC peripheral. Only supports software triggered - * conversions. + * @brief Initialize an ADC peripheral. + * + * Initializes the RCC clock line for the given peripheral, using ADC + * prescaler RCC_ADCPRE_PCLK_DIV_6. Resets ADC device registers. + * * @param dev ADC peripheral to initialize - * @param flags unused */ -void adc_init(const adc_dev *dev, uint32 flags) { - /* Spin up the clocks */ +void adc_init(const adc_dev *dev) { rcc_set_prescaler(RCC_PRESCALER_ADC, RCC_ADCPRE_PCLK_DIV_6); rcc_clk_enable(dev->clk_id); rcc_reset_dev(dev->clk_id); - - /* Software triggers conversions, conversion on external events */ - adc_set_extsel(dev, 7); - adc_set_exttrig(dev, 1); - - /* Enable the ADC */ - adc_enable(dev); - - /* Calibrate ADC */ - adc_calibrate(dev); } /** * @brief Set external event select for regular group - * @param dev adc device - * @param trigger event to select. See ADC_CR2 EXTSEL[2:0] bits. + * @param dev ADC device + * @param event Event used to trigger the start of conversion. + * @see adc_extsel_event */ -void adc_set_extsel(const adc_dev *dev, uint8 trigger) { +void adc_set_extsel(const adc_dev *dev, adc_extsel_event event) { uint32 cr2 = dev->regs->CR2; cr2 &= ~ADC_CR2_EXTSEL; - cr2 |= (trigger & 0x7) << 17; + cr2 |= event; dev->regs->CR2 = cr2; } +/** + * @brief Call a function on all ADC devices. + * @param fn Function to call on each ADC device. + */ +void adc_foreach(void (*fn)(const adc_dev*)) { + fn(ADC1); + fn(ADC2); +#ifdef STM32_HIGH_DENSITY + fn(ADC3); +#endif +} /** * @brief Turn the given sample rate into values for ADC_SMPRx. Don't @@ -125,7 +126,7 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { * @brief Calibrate an ADC peripheral * @param dev adc device */ -static void adc_calibrate(const adc_dev *dev) { +void adc_calibrate(const adc_dev *dev) { __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3); __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2); @@ -137,3 +138,23 @@ static void adc_calibrate(const adc_dev *dev) { while (*cal_bit) ; } + +/** + * @brief Perform a single synchronous software triggered conversion on a + * channel. + * @param dev ADC device to use for reading. + * @param channel channel to convert + * @return conversion result + */ +uint16 adc_read(const adc_dev *dev, uint8 channel) { + adc_reg_map *regs = dev->regs; + + adc_set_reg_seqlen(dev, 1); + + regs->SQR3 = channel; + regs->CR2 |= ADC_CR2_SWSTART; + while(!(regs->SR & ADC_SR_EOC)) + ; + + return (uint16)(regs->DR & ADC_DR_DATA); +} diff --git a/libmaple/adc.h b/libmaple/adc.h index 53ef032..520b982 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -79,103 +79,253 @@ extern const adc_dev *ADC3; #endif /* - * ADC peripheral base addresses + * Register map base pointers */ /** ADC1 register map base pointer. */ -#define ADC1_BASE ((adc_reg_map*)0x40012400) +#define ADC1_BASE ((adc_reg_map*)0x40012400) /** ADC2 register map base pointer. */ -#define ADC2_BASE ((adc_reg_map*)0x40012800) +#define ADC2_BASE ((adc_reg_map*)0x40012800) /** ADC3 register map base pointer. */ -#define ADC3_BASE ((adc_reg_map*)0x40013C00) +#define ADC3_BASE ((adc_reg_map*)0x40013C00) /* * Register bit definitions */ /* Status register */ -#define ADC_SR_AWD BIT(0) -#define ADC_SR_EOC BIT(1) -#define ADC_SR_JEOC BIT(2) -#define ADC_SR_JSTRT BIT(3) -#define ADC_SR_STRT BIT(4) + +#define ADC_SR_AWD_BIT 0 +#define ADC_SR_EOC_BIT 1 +#define ADC_SR_JEOC_BIT 2 +#define ADC_SR_JSTRT_BIT 3 +#define ADC_SR_STRT_BIT 4 + +#define ADC_SR_AWD BIT(ADC_SR_AWD_BIT) +#define ADC_SR_EOC BIT(ADC_SR_EOC_BIT) +#define ADC_SR_JEOC BIT(ADC_SR_JEOC_BIT) +#define ADC_SR_JSTRT BIT(ADC_SR_JSTRT_BIT) +#define ADC_SR_STRT BIT(ADC_SR_STRT_BIT) /* Control register 1 */ -#define ADC_CR1_AWDCH (0x1F) -#define ADC_CR1_EOCIE BIT(5) -#define ADC_CR1_AWDIE BIT(6) -#define ADC_CR1_JEOCIE BIT(7) -#define ADC_CR1_SCAN BIT(8) -#define ADC_CR1_AWDSGL BIT(9) -#define ADC_CR1_JAUTO BIT(10) -#define ADC_CR1_DISCEN BIT(11) -#define ADC_CR1_JDISCEN BIT(12) -#define ADC_CR1_DISCNUM (0xE000) -#define ADC_CR1_JAWDEN BIT(22) -#define ADC_CR1_AWDEN BIT(23) + +#define ADC_CR1_EOCIE_BIT 5 +#define ADC_CR1_AWDIE_BIT 6 +#define ADC_CR1_JEOCIE_BIT 7 +#define ADC_CR1_SCAN_BIT 8 +#define ADC_CR1_AWDSGL_BIT 9 +#define ADC_CR1_JAUTO_BIT 10 +#define ADC_CR1_DISCEN_BIT 11 +#define ADC_CR1_JDISCEN_BIT 12 +#define ADC_CR1_JAWDEN_BIT 22 +#define ADC_CR1_AWDEN_BIT 23 + +#define ADC_CR1_AWDCH (0x1F) +#define ADC_CR1_EOCIE BIT(ADC_CR1_EOCIE_BIT) +#define ADC_CR1_AWDIE BIT(ADC_CR1_AWDIE_BIT) +#define ADC_CR1_JEOCIE BIT(ADC_CR1_JEOCIE_BIT) +#define ADC_CR1_SCAN BIT(ADC_CR1_SCAN_BIT) +#define ADC_CR1_AWDSGL BIT(ADC_CR1_AWDSGL_BIT) +#define ADC_CR1_JAUTO BIT(ADC_CR1_JAUTO_BIT) +#define ADC_CR1_DISCEN BIT(ADC_CR1_DISCEN_BIT) +#define ADC_CR1_JDISCEN BIT(ADC_CR1_JDISCEN_BIT) +#define ADC_CR1_DISCNUM (0xE000) +#define ADC_CR1_JAWDEN BIT(ADC_CR1_JAWDEN_BIT) +#define ADC_CR1_AWDEN BIT(ADC_CR1_AWDEN_BIT) /* Control register 2 */ -#define ADC_CR2_ADON BIT(0) -#define ADC_CR2_CONT BIT(1) -#define ADC_CR2_CAL BIT(2) -#define ADC_CR2_RSTCAL BIT(3) -#define ADC_CR2_DMA BIT(8) -#define ADC_CR2_ALIGN BIT(11) -#define ADC_CR2_JEXTSEL (0x7000) -#define ADC_CR2_JEXTTRIG BIT(15) -#define ADC_CR2_EXTSEL (0xE0000) -#define ADC_CR2_EXTTRIG BIT(20) -#define ADC_CR2_JSWSTART BIT(21) -#define ADC_CR2_SWSTART BIT(22) -#define ADC_CR2_TSEREFE BIT(23) - -void adc_init(const adc_dev *dev, uint32 flags); -void adc_set_extsel(const adc_dev *dev, uint8 trigger); -/** ADC per-sample conversion times, in ADC clock cycles */ -typedef enum { - ADC_SMPR_1_5, ///< 1.5 ADC cycles - ADC_SMPR_7_5, ///< 7.5 ADC cycles - ADC_SMPR_13_5, ///< 13.5 ADC cycles - ADC_SMPR_28_5, ///< 28.5 ADC cycles - ADC_SMPR_41_5, ///< 41.5 ADC cycles - ADC_SMPR_55_5, ///< 55.5 ADC cycles - ADC_SMPR_71_5, ///< 71.5 ADC cycles - ADC_SMPR_239_5 ///< 239.5 ADC cycles -} adc_smp_rate; +#define ADC_CR2_ADON_BIT 0 +#define ADC_CR2_CONT_BIT 1 +#define ADC_CR2_CAL_BIT 2 +#define ADC_CR2_RSTCAL_BIT 3 +#define ADC_CR2_DMA_BIT 8 +#define ADC_CR2_ALIGN_BIT 11 +#define ADC_CR2_JEXTTRIG_BIT 15 +#define ADC_CR2_EXTTRIG_BIT 20 +#define ADC_CR2_JSWSTART_BIT 21 +#define ADC_CR2_SWSTART_BIT 22 +#define ADC_CR2_TSEREFE_BIT 23 -void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); +#define ADC_CR2_ADON BIT(ADC_CR2_ADON_BIT) +#define ADC_CR2_CONT BIT(ADC_CR2_CONT_BIT) +#define ADC_CR2_CAL BIT(ADC_CR2_CAL_BIT) +#define ADC_CR2_RSTCAL BIT(ADC_CR2_RSTCAL_BIT) +#define ADC_CR2_DMA BIT(ADC_CR2_DMA_BIT) +#define ADC_CR2_ALIGN BIT(ADC_CR2_ALIGN_BIT) +#define ADC_CR2_JEXTSEL (0x7000) +#define ADC_CR2_JEXTTRIG BIT(ADC_CR2_JEXTTRIG_BIT) +#define ADC_CR2_EXTSEL (0xE0000) +#define ADC_CR2_EXTTRIG BIT(ADC_CR2_EXTTRIG_BIT) +#define ADC_CR2_JSWSTART BIT(ADC_CR2_JSWSTART_BIT) +#define ADC_CR2_SWSTART BIT(ADC_CR2_SWSTART_BIT) +#define ADC_CR2_TSEREFE BIT(ADC_CR2_TSEREFE_BIT) + +/* Sample time register 1 */ + +#define ADC_SMPR1_SMP17 (0x7 << 21) +#define ADC_SMPR1_SMP16 (0x7 << 18) +#define ADC_SMPR1_SMP15 (0x7 << 15) +#define ADC_SMPR1_SMP14 (0x7 << 12) +#define ADC_SMPR1_SMP13 (0x7 << 9) +#define ADC_SMPR1_SMP12 (0x7 << 6) +#define ADC_SMPR1_SMP11 (0x7 << 3) +#define ADC_SMPR1_SMP10 0x7 + +/* Sample time register 2 */ + +#define ADC_SMPR2_SMP9 (0x7 << 27) +#define ADC_SMPR2_SMP8 (0x7 << 24) +#define ADC_SMPR2_SMP7 (0x7 << 21) +#define ADC_SMPR2_SMP6 (0x7 << 18) +#define ADC_SMPR2_SMP5 (0x7 << 15) +#define ADC_SMPR2_SMP4 (0x7 << 12) +#define ADC_SMPR2_SMP3 (0x7 << 9) +#define ADC_SMPR2_SMP2 (0x7 << 6) +#define ADC_SMPR2_SMP1 (0x7 << 3) +#define ADC_SMPR2_SMP0 0x7 + +/* Injected channel data offset register */ + +#define ADC_JOFR_JOFFSET 0x3FF + +/* Watchdog high threshold register */ + +#define ADC_HTR_HT 0x3FF + +/* Watchdog low threshold register */ + +#define ADC_LTR_LT 0x3FF + +/* Regular sequence register 1 */ + +#define ADC_SQR1_L (0x1F << 20) +#define ADC_SQR1_SQ16 (0x1F << 15) +#define ADC_SQR1_SQ15 (0x1F << 10) +#define ADC_SQR1_SQ14 (0x1F << 5) +#define ADC_SQR1_SQ13 0x1F + +/* Regular sequence register 2 */ + +#define ADC_SQR2_SQ12 (0x1F << 25) +#define ADC_SQR2_SQ11 (0x1F << 20) +#define ADC_SQR2_SQ10 (0x1F << 16) +#define ADC_SQR2_SQ9 (0x1F << 10) +#define ADC_SQR2_SQ8 (0x1F << 5) +#define ADC_SQR2_SQ7 0x1F + +/* Regular sequence register 3 */ + +#define ADC_SQR3_SQ6 (0x1F << 25) +#define ADC_SQR3_SQ5 (0x1F << 20) +#define ADC_SQR3_SQ4 (0x1F << 16) +#define ADC_SQR3_SQ3 (0x1F << 10) +#define ADC_SQR3_SQ2 (0x1F << 5) +#define ADC_SQR3_SQ1 0x1F + +/* Injected sequence register */ + +#define ADC_JSQR_JL (0x3 << 20) +#define ADC_JSQR_JL_1CONV (0x0 << 20) +#define ADC_JSQR_JL_2CONV (0x1 << 20) +#define ADC_JSQR_JL_3CONV (0x2 << 20) +#define ADC_JSQR_JL_4CONV (0x3 << 20) +#define ADC_JSQR_JSQ4 (0x1F << 15) +#define ADC_JSQR_JSQ3 (0x1F << 10) +#define ADC_JSQR_JSQ2 (0x1F << 5) +#define ADC_JSQR_JSQ1 0x1F + +/* Injected data registers */ + +#define ADC_JDR_JDATA 0xFFFF + +/* Regular data register */ + +#define ADC_DR_ADC2DATA (0xFFFF << 16) +#define ADC_DR_DATA 0xFFFF + +void adc_init(const adc_dev *dev); /** - * @brief Perform a single synchronous software triggered conversion on a - * channel. - * @param dev ADC device to use for reading. - * @param channel channel to convert - * @return conversion result + * @brief External event selector for regular group conversion. + * @see adc_set_extsel */ -static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { - adc_reg_map *regs = dev->regs; +typedef enum adc_extsel_event { + ADC_ADC12_TIM1_CC1 = (0 << 17), /**< ADC1 and ADC2: Timer 1 CC1 event */ + ADC_ADC12_TIM1_CC2 = (1 << 17), /**< ADC1 and ADC2: Timer 1 CC2 event */ + ADC_ADC12_TIM1_CC3 = (2 << 17), /**< ADC1 and ADC2: Timer 1 CC3 event */ + ADC_ADC12_TIM2_CC2 = (3 << 17), /**< ADC1 and ADC2: Timer 2 CC2 event */ + ADC_ADC12_TIM3_TRGO = (4 << 17), /**< ADC1 and ADC2: Timer 3 TRGO event */ + ADC_ADC12_TIM4_CC4 = (5 << 17), /**< ADC1 and ADC2: Timer 4 CC4 event */ + ADC_ADC12_EXTI11 = (6 << 17), /**< ADC1 and ADC2: EXTI11 event */ +#ifdef STM32_HIGH_DENSITY + ADC_ADC12_TIM8_TRGO = (6 << 17), /**< ADC1 and ADC2: Timer 8 TRGO + event (high density only) */ +#endif + ADC_ADC12_SWSTART = (7 << 17), /**< ADC1 and ADC2: Software start */ +#ifdef STM32_HIGH_DENSITY + ADC_ADC3_TIM3_CC1 = (0 << 17), /**< ADC3: Timer 3 CC1 event + (high density only) */ + ADC_ADC3_TIM2_CC3 = (1 << 17), /**< ADC3: Timer 2 CC3 event + (high density only) */ + ADC_ADC3_TIM1_CC3 = (2 << 17), /**< ADC3: Timer 1 CC3 event + (high density only) */ + ADC_ADC3_TIM8_CC1 = (3 << 17), /**< ADC3: Timer 8 CC1 event + (high density only) */ + ADC_ADC3_TIM8_TRGO = (4 << 17), /**< ADC3: Timer 8 TRGO event + (high density only) */ + ADC_ADC3_TIM5_CC1 = (5 << 17), /**< ADC3: Timer 5 CC1 event + (high density only) */ + ADC_ADC3_TIM5_CC3 = (6 << 17), /**< ADC3: Timer 5 CC3 event + (high density only) */ + ADC_ADC3_SWSTART = (7 << 17), /**< ADC3: Software start (high + density only) */ +#endif + ADC_SWSTART = (7 << 17) /**< ADC1, ADC2, ADC3: Software start */ +} adc_extsel_event; - /* Set target channel */ - regs->SQR3 = channel; +void adc_set_extsel(const adc_dev *dev, adc_extsel_event event); +void adc_foreach(void (*fn)(const adc_dev*)); - /* Start the conversion */ - regs->CR2 |= ADC_CR2_SWSTART; +/** ADC per-sample conversion times, in ADC clock cycles */ +typedef enum { + ADC_SMPR_1_5, /**< 1.5 ADC cycles */ + ADC_SMPR_7_5, /**< 7.5 ADC cycles */ + ADC_SMPR_13_5, /**< 13.5 ADC cycles */ + ADC_SMPR_28_5, /**< 28.5 ADC cycles */ + ADC_SMPR_41_5, /**< 41.5 ADC cycles */ + ADC_SMPR_55_5, /**< 55.5 ADC cycles */ + ADC_SMPR_71_5, /**< 71.5 ADC cycles */ + ADC_SMPR_239_5 /**< 239.5 ADC cycles */ +} adc_smp_rate; - /* Wait for it to finish */ - while((regs->SR & ADC_SR_EOC) == 0) - ; +void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); +void adc_calibrate(const adc_dev *dev); +uint16 adc_read(const adc_dev *dev, uint8 channel); - return regs->DR; +/** + * @brief Set the regular channel sequence length. + * + * Defines the total number of conversions in the regular channel + * conversion sequence. + * + * @param length Regular channel sequence length, from 1 to 16. + */ +static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8 length) { + uint32 tmp = dev->regs->SQR1; + tmp &= ~ADC_SQR1_L; + tmp |= (length - 1) << 20; + dev->regs->SQR1 = tmp; } /** * @brief Set external trigger conversion mode event for regular channels * @param dev ADC device - * @param enable If 1, conversion on external events is enabled, 0 to disable + * @param enable If 1, conversion on external events is enabled; if 0, + * disabled. */ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { - *bb_perip(&dev->regs->CR2, 20) = !!enable; + *bb_perip(&dev->regs->CR2, ADC_CR2_EXTTRIG_BIT) = !!enable; } /** @@ -183,7 +333,7 @@ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { * @param dev ADC device to enable */ static inline void adc_enable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 1; + *bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 1; } /** @@ -191,18 +341,14 @@ static inline void adc_enable(const adc_dev *dev) { * @param dev ADC device to disable */ static inline void adc_disable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 0; + *bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 0; } /** - * @brief Disable all ADCs + * @brief Disable all ADC peripherals. */ static inline void adc_disable_all(void) { - adc_disable(ADC1); - adc_disable(ADC2); -#ifdef STM32_HIGH_DENSITY - adc_disable(ADC3); -#endif + adc_foreach(adc_disable); } #ifdef __cplusplus diff --git a/libmaple/timer.c b/libmaple/timer.c index ad0ec6f..a4e4032 100644 --- a/libmaple/timer.c +++ b/libmaple/timer.c @@ -189,8 +189,8 @@ void timer_set_mode(timer_dev *dev, uint8 channel, timer_mode mode) { } /** - * @brief Call a given function on all timers. - * @param fn Function to call on each timer. + * @brief Call a function on timer devices. + * @param fn Function to call on each timer device. */ void timer_foreach(void (*fn)(timer_dev*)) { fn(TIMER1); diff --git a/notes/coding_standard.txt b/notes/coding_standard.txt index 372ebf4..b81847d 100644 --- a/notes/coding_standard.txt +++ b/notes/coding_standard.txt @@ -220,3 +220,47 @@ General Formatting (require 'lineker) (dolist (hook '(c-mode-hook c++-mode-hook)) (add-hook hook (lambda () (lineker-mode 1)))) + +Language Features and Compiler Extensions +----------------------------------------- + +- In libmaple proper, aim for C99 compatibility. Some GCC extensions + are OK, but let's not go crazy. + +- If you'd like to get code into libmaple which uses a GCC extension + not already in use elsewhere, ask a LeafLabs developer (or another + one, if you are one) what they think about it first. + +- Explicitly approved GCC extensions: + + * asm volatile: + http://gcc.gnu.org/onlinedocs/gcc/Extended-Asm.html + + * Nested functions: + http://gcc.gnu.org/onlinedocs/gcc/Nested-Functions.html + +- In wirish, generally be very conservative when using C++ features + that aren't part of C. We are forced to use C++ for Arduino + compatibility (and the general Arduino style of pretending that an + object is a library), but it's an angry beast, and we don't want to + provoke it. The mantra is "C with classes". + +- Explicitly approved C++ features: + + * Initializers that aren't constant; e.g. the gpio_dev* values in + PIN_MAPs. + + * Default arguments: e.g., the timeout argument defaulting to 0 + (meaning to wait forever) in waitForButtonPress(). + +- Explicitly forbidden C++ features: + + * Templates + +- C++ features that are conditionally allowed, but require explicit + approval from at least two libmaple developers (one of which may be + yourself): + + * Operator overloading: Never allowed when it's just for style. + Potentially allowed when you're implementing a class that models a + mathematical structure, and you'd like to implement e.g. operator+(). diff --git a/notes/native-pin-definitions.txt b/notes/native-pin-definitions.txt deleted file mode 100644 index b871f89..0000000 --- a/notes/native-pin-definitions.txt +++ /dev/null @@ -1,201 +0,0 @@ -Maple Native (STM32F103ZE) pin definitions, by GPIO bank. - -Source: ST DOC ID 14611, Datasheet for STM32F103xC, STM32F103xD, -STM32F103xE, Table 5, pp. 30--35. - -Some peripherals and extra functionality with less/no libmaple -relevance (at time of writing) are given in "Other" following each -bank's main table. Non-default alternate functions are not listed. If -wirish will/does remap the pin's main function after reset, the main -function is listed under "Other". - -This document was prepared carefully and is believed to be complete -and correct, but the final arbiter of truth is the ST datasheet. - -*** NB: UART 4 and 5 are NOT USART (columns are labeled appropriately). - ---------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? ---------------------------------------------------------------------------- -PA0 123in0 2ch1etr - - - 2cts - - - - 5ch1 - 8etr -PA1 123in1 5ch2 - - - 2rts - - - - 2ch2 -PA2 123in2 5ch3 - - - 2tx - - - - 2ch3 -PA3 123in3 5ch4 - - - 2rx - - - - 2ch4 -PA4 12in4 - - - - 2ck 1nss out1 - -PA5 12in5 - - - - - 1sck out2 - -PA6 12in6 8bkin - - - - 1miso - - - 3ch1 -PA7 12in7 8ch1n - - - - 1mosi - - - 3ch2 -PA8 - 1ch1 - - - 1ck - - Y -PA9 - 1ch2 - - - 1tx - - Y -PA10 - 1ch3 - - - 1rx - - Y -PA11 - 1ch4 - - - 1cts - - Y -PA12 - 1etr - - - 1rts - - Y -PA13 - - - - - - - - Y -PA14 - - - - - - - - Y -PA15 - - - 3ws - - 3nss - Y - -Other: - -PA0: WKUP -PA8: MCO -PA11: USBDM, CAN_RX -PA12: USBDP, CAN_TX -PA13: JTMS-SWDIO (default) -PA14: JTCK-SWCLK (default) -PA15: JTDI (default) - -------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? SDIO -------------------------------------------------------------------------------- -PB0 12in8 3ch3 - - - - - - - - - 8ch2n -PB1 12in9 3ch4 - - - - - - - - - 8ch3n -PB2 - - - - - - - - Y - -PB3 - - - 3ck - - 3sck - Y - -PB4 - - - - - - 3miso - Y - -PB5 - - - 3sd 1smba - 3mosi - - - -PB6 - 4ch1 - - 1scl - - - Y - -PB7 - 4ch2 NADV - 1sda - - - Y - -PB8 - 4ch3 - - - - - - Y D4 -PB9 - 4ch4 - - - - - - Y D5 -PB10 - - - - 2scl 3tx - - Y - -PB11 - - - - 2sda 3rx - - Y - -PB12 - 1bkin - 2ws 2smba 3ck 2nss - Y - -PB13 - 1ch1n - 2ck - 3cts 2sck - Y - -PB14 - 1ch2n - - - 3rts 2miso - Y - -PB15 - 1ch3n - 2sd - - 2mosi - Y - - -Other: - -PB2: BOOT1 -PB3: JTDO (default) -PB4: NJTRST (default) - -------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO -------------------------------------------------------------------------------- -PC0 123in10 - - - - - - - - - -PC1 123in11 - - - - - - - - - -PC2 123in12 - - - - - - - - - -PC3 123in13 - - - - - - - - - -PC4 12in14 - - - - - - - - - -PC5 12in15 - - - - - - - - - -PC6 - 8ch1 - 2mck - - - - Y D6 -PC7 - 8ch2 - 3mck - - - - Y D7 -PC8 - 8ch3 - - - - - - Y D0 -PC9 - 8ch4 - - - - - - Y D1 -PC10 - - - - - 4tx - - Y D2 -PC11 - - - - - 4rx - - Y D3 -PC12 - - - - - 5tx - - Y CK -PC13 - - - - - - - - - - -PC14 - - - - - - - - - - -PC15 - - - - - - - - - - - -Other: - -PC13: TAMPER_RTC -PC14: OSC32_IN -PC15: OSC32_OUT - -------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO -------------------------------------------------------------------------------- -PD0 - - D2 - - - - - Y - -PD1 - - D3 - - - - - Y - -PD2 - 3etr - - - 5rx - - Y CMD -PD3 - - CLK - - - - - Y - -PD4 - - NOE - - - - - Y - -PD5 - - NWE - - - - - Y - -PD6 - - NWAIT - - - - - Y - -PD7 - - NE1 - - - - - Y - - NCE2 -PD8 - - D13 - - - - - Y - -PD9 - - D14 - - - - - Y - -PD10 - - D15 - - - - - Y - -PD11 - - A16 - - - - - Y - -PD12 - - A17 - - - - - Y - -PD13 - - A18 - - - - - Y - -PD14 - - D0 - - - - - Y - -PD15 - - D1 - - - - - Y - - -Other: - -PD0: OSC_IN (default) -PD1: OSC_OUT (default) - ---------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? ---------------------------------------------------------------------------- -PE0 - 4etr NBL0 - - - - - Y -PE1 - - NBL1 - - - - - Y -PE2 - - A23 - - - - - Y -PE3 - - A19 - - - - - Y -PE4 - - A20 - - - - - Y -PE5 - - A21 - - - - - Y -PE6 - - A22 - - - - - Y -PE7 - - D4 - - - - - Y -PE8 - - D5 - - - - - Y -PE9 - - D6 - - - - - Y -PE10 - - D7 - - - - - Y -PE11 - - D8 - - - - - Y -PE12 - - D9 - - - - - Y -PE13 - - D10 - - - - - Y -PE14 - - D11 - - - - - Y -PE15 - - D12 - - - - - Y - -Other: -PE2: TRACECK -PE3: TRACED0 -PE4: TRACED1 -PE5: TRACED2 -PE6: TRACED3 - ---------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? ---------------------------------------------------------------------------- -PF0 - - A0 - - - - - Y -PF1 - - A1 - - - - - Y -PF2 - - A2 - - - - - Y -PF3 - - A3 - - - - - Y -PF4 - - A4 - - - - - Y -PF5 - - A5 - - - - - Y -PF6 3in4 - NIORD - - - - - - -PF7 3in5 - NREG - - - - - - -PF8 3in6 - NIOWR - - - - - - -PF9 3in7 - CD - - - - - - -PF10 3in8 - INTR - - - - - - -PF11 - - NIOS16 - - - - - Y -PF12 - - A6 - - - - - Y -PF13 - - A7 - - - - - Y -PF14 - - A8 - - - - - Y -PF15 - - A9 - - - - - Y - ---------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? ---------------------------------------------------------------------------- -PG0 - - A10 - - - - - Y -PG1 - - A11 - - - - - Y -PG2 - - A12 - - - - - Y -PG3 - - A13 - - - - - Y -PG4 - - A14 - - - - - Y -PG5 - - A15 - - - - - Y -PG6 - - INT2 - - - - - Y -PG7 - - INT3 - - - - - Y -PG8 - - - - - - - - Y -PG9 - - NE2 - - - - - Y - NCE3 -PG10 - - NCE4_1 - - - - - Y - NE3 -PG11 - - NCE4_2 - - - - - Y -PG12 - - NE4 - - - - - Y -PG13 - - A24 - - - - - Y -PG14 - - A25 - - - - - Y -PG15 - - - - - - - - Y diff --git a/notes/pin-definitions.txt b/notes/pin-definitions.txt new file mode 100644 index 0000000..71572ac --- /dev/null +++ b/notes/pin-definitions.txt @@ -0,0 +1,201 @@ +Pin definitions by GPIO bank. + +Source: ST DOC ID 14611, Datasheet for STM32F103xC, STM32F103xD, +STM32F103xE, Table 5, pp. 30--35. + +Some peripherals and extra functionality with less/no libmaple +relevance (at time of writing) are given in "Other" following each +bank's main table. Non-default alternate functions are not listed. If +wirish will/does remap the pin's main function after reset, the main +function is listed under "Other". + +This document was prepared carefully and is believed to be correct, +but the final arbiter of truth is the ST datasheet. + +*** NB: UART 4 and 5 are NOT USART (columns are labeled appropriately). + +--------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? +--------------------------------------------------------------------------- +PA0 123in0 2ch1etr - - - 2cts - - - + 5ch1 + 8etr +PA1 123in1 5ch2 - - - 2rts - - - + 2ch2 +PA2 123in2 5ch3 - - - 2tx - - - + 2ch3 +PA3 123in3 5ch4 - - - 2rx - - - + 2ch4 +PA4 12in4 - - - - 2ck 1nss out1 - +PA5 12in5 - - - - - 1sck out2 - +PA6 12in6 8bkin - - - - 1miso - - + 3ch1 +PA7 12in7 8ch1n - - - - 1mosi - - + 3ch2 +PA8 - 1ch1 - - - 1ck - - Y +PA9 - 1ch2 - - - 1tx - - Y +PA10 - 1ch3 - - - 1rx - - Y +PA11 - 1ch4 - - - 1cts - - Y +PA12 - 1etr - - - 1rts - - Y +PA13 - - - - - - - - Y +PA14 - - - - - - - - Y +PA15 - - - 3ws - - 3nss - Y + +Other: + +PA0: WKUP +PA8: MCO +PA11: USBDM, CAN_RX +PA12: USBDP, CAN_TX +PA13: JTMS-SWDIO (default) +PA14: JTCK-SWCLK (default) +PA15: JTDI (default) + +------------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? SDIO +------------------------------------------------------------------------------- +PB0 12in8 3ch3 - - - - - - - - + 8ch2n +PB1 12in9 3ch4 - - - - - - - - + 8ch3n +PB2 - - - - - - - - Y - +PB3 - - - 3ck - - 3sck - Y - +PB4 - - - - - - 3miso - Y - +PB5 - - - 3sd 1smba - 3mosi - - - +PB6 - 4ch1 - - 1scl - - - Y - +PB7 - 4ch2 NADV - 1sda - - - Y - +PB8 - 4ch3 - - - - - - Y D4 +PB9 - 4ch4 - - - - - - Y D5 +PB10 - - - - 2scl 3tx - - Y - +PB11 - - - - 2sda 3rx - - Y - +PB12 - 1bkin - 2ws 2smba 3ck 2nss - Y - +PB13 - 1ch1n - 2ck - 3cts 2sck - Y - +PB14 - 1ch2n - - - 3rts 2miso - Y - +PB15 - 1ch3n - 2sd - - 2mosi - Y - + +Other: + +PB2: BOOT1 +PB3: JTDO (default) +PB4: NJTRST (default) + +------------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO +------------------------------------------------------------------------------- +PC0 123in10 - - - - - - - - - +PC1 123in11 - - - - - - - - - +PC2 123in12 - - - - - - - - - +PC3 123in13 - - - - - - - - - +PC4 12in14 - - - - - - - - - +PC5 12in15 - - - - - - - - - +PC6 - 8ch1 - 2mck - - - - Y D6 +PC7 - 8ch2 - 3mck - - - - Y D7 +PC8 - 8ch3 - - - - - - Y D0 +PC9 - 8ch4 - - - - - - Y D1 +PC10 - - - - - 4tx - - Y D2 +PC11 - - - - - 4rx - - Y D3 +PC12 - - - - - 5tx - - Y CK +PC13 - - - - - - - - - - +PC14 - - - - - - - - - - +PC15 - - - - - - - - - - + +Other: + +PC13: TAMPER_RTC +PC14: OSC32_IN +PC15: OSC32_OUT + +------------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO +------------------------------------------------------------------------------- +PD0 - - D2 - - - - - Y - +PD1 - - D3 - - - - - Y - +PD2 - 3etr - - - 5rx - - Y CMD +PD3 - - CLK - - - - - Y - +PD4 - - NOE - - - - - Y - +PD5 - - NWE - - - - - Y - +PD6 - - NWAIT - - - - - Y - +PD7 - - NE1 - - - - - Y - + NCE2 +PD8 - - D13 - - - - - Y - +PD9 - - D14 - - - - - Y - +PD10 - - D15 - - - - - Y - +PD11 - - A16 - - - - - Y - +PD12 - - A17 - - - - - Y - +PD13 - - A18 - - - - - Y - +PD14 - - D0 - - - - - Y - +PD15 - - D1 - - - - - Y - + +Other: + +PD0: OSC_IN (default) +PD1: OSC_OUT (default) + +--------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? +--------------------------------------------------------------------------- +PE0 - 4etr NBL0 - - - - - Y +PE1 - - NBL1 - - - - - Y +PE2 - - A23 - - - - - Y +PE3 - - A19 - - - - - Y +PE4 - - A20 - - - - - Y +PE5 - - A21 - - - - - Y +PE6 - - A22 - - - - - Y +PE7 - - D4 - - - - - Y +PE8 - - D5 - - - - - Y +PE9 - - D6 - - - - - Y +PE10 - - D7 - - - - - Y +PE11 - - D8 - - - - - Y +PE12 - - D9 - - - - - Y +PE13 - - D10 - - - - - Y +PE14 - - D11 - - - - - Y +PE15 - - D12 - - - - - Y + +Other: +PE2: TRACECK +PE3: TRACED0 +PE4: TRACED1 +PE5: TRACED2 +PE6: TRACED3 + +--------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? +--------------------------------------------------------------------------- +PF0 - - A0 - - - - - Y +PF1 - - A1 - - - - - Y +PF2 - - A2 - - - - - Y +PF3 - - A3 - - - - - Y +PF4 - - A4 - - - - - Y +PF5 - - A5 - - - - - Y +PF6 3in4 - NIORD - - - - - - +PF7 3in5 - NREG - - - - - - +PF8 3in6 - NIOWR - - - - - - +PF9 3in7 - CD - - - - - - +PF10 3in8 - INTR - - - - - - +PF11 - - NIOS16 - - - - - Y +PF12 - - A6 - - - - - Y +PF13 - - A7 - - - - - Y +PF14 - - A8 - - - - - Y +PF15 - - A9 - - - - - Y + +--------------------------------------------------------------------------- +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? +--------------------------------------------------------------------------- +PG0 - - A10 - - - - - Y +PG1 - - A11 - - - - - Y +PG2 - - A12 - - - - - Y +PG3 - - A13 - - - - - Y +PG4 - - A14 - - - - - Y +PG5 - - A15 - - - - - Y +PG6 - - INT2 - - - - - Y +PG7 - - INT3 - - - - - Y +PG8 - - - - - - - - Y +PG9 - - NE2 - - - - - Y + NCE3 +PG10 - - NCE4_1 - - - - - Y + NE3 +PG11 - - NCE4_2 - - - - - Y +PG12 - - NE4 - - - - - Y +PG13 - - A24 - - - - - Y +PG14 - - A25 - - - - - Y +PG15 - - - - - - - - Y diff --git a/wirish/boards.cpp b/wirish/boards.cpp new file mode 100644 index 0000000..17f47c6 --- /dev/null +++ b/wirish/boards.cpp @@ -0,0 +1,145 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief Generic board initialization routines. + * + * By default, we bring up all Maple boards to 72MHz, clocked off the + * PLL, driven by the 8MHz external crystal. AHB and APB2 are clocked + * at 72MHz. APB1 is clocked at 36MHz. + */ + +#include "wirish.h" + +#include "flash.h" +#include "rcc.h" +#include "nvic.h" +#include "systick.h" +#include "gpio.h" +#include "adc.h" +#include "timer.h" +#include "usb.h" + +static void setupFlash(void); +static void setupClocks(void); +static void setupADC(void); +static void setupTimers(void); + +/** + * @brief Generic board initialization function. + * + * This function is called before main(). It ensures that the clocks + * and peripherals are configured properly for use with wirish, then + * calls boardInit(). + * + * @see boardInit() + */ +void init(void) { + setupFlash(); + setupClocks(); + nvic_init(); + systick_init(SYSTICK_RELOAD_VAL); + gpio_init_all(); + afio_init(); + setupADC(); + setupTimers(); + setupUSB(); + boardInit(); +} + +static void setupFlash(void) { + flash_enable_prefetch(); + flash_set_latency(FLASH_WAIT_STATE_2); +} + +/* + * Clock setup. Note that some of this only takes effect if we're + * running bare metal and the bootloader hasn't done it for us + * already. + * + * If you change this function, you MUST change the file-level Doxygen + * comment above. + */ +static void setupClocks() { + rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); + rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); + rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); + rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); +} + +static void adcDefaultConfig(const adc_dev* dev); + +static void setupADC() { + adc_foreach(adcDefaultConfig); +} + +static void timerDefaultConfig(timer_dev*); + +static void setupTimers() { + timer_foreach(timerDefaultConfig); +} + +static void adcDefaultConfig(const adc_dev *dev) { + adc_init(dev); + + adc_set_extsel(dev, ADC_SWSTART); + adc_set_exttrig(dev, true); + + adc_enable(dev); + adc_calibrate(dev); + adc_set_sample_rate(dev, ADC_SMPR_55_5); +} + +static void timerDefaultConfig(timer_dev *dev) { + timer_adv_reg_map *regs = (dev->regs).adv; + const uint16 full_overflow = 0xFFFF; + const uint16 half_duty = 0x8FFF; + + timer_init(dev); + timer_pause(dev); + + regs->CR1 = TIMER_CR1_ARPE; + regs->PSC = 1; + regs->SR = 0; + regs->DIER = 0; + regs->EGR = TIMER_EGR_UG; + + switch (dev->type) { + case TIMER_ADVANCED: + regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; + // fall-through + case TIMER_GENERAL: + timer_set_reload(dev, full_overflow); + + for (int channel = 1; channel <= 4; channel++) { + timer_set_compare(dev, channel, half_duty); + timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, TIMER_OC_PE); + } + // fall-through + case TIMER_BASIC: + break; + } + + timer_resume(dev); +} diff --git a/wirish/boards.h b/wirish/boards.h index b72609d..3d023ae 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -60,12 +60,22 @@ enum { D106, D107, D108, D109, D110, D111, }; /** - * @brief Maps each pin to a corresponding struct stm32_pin_info. - * @see struct stm32_pin_info + * @brief Maps each Maple pin to a corresponding stm32_pin_info. + * @see stm32_pin_info */ extern stm32_pin_info PIN_MAP[]; -/** Board-specific initialization function. */ +void init(void); + +/** + * @brief Board-specific initialization function. + * + * This function is called from init() after all generic board + * initialization has been performed. Each board is required to + * define its own. + * + * @see init() + */ extern void boardInit(void); #ifdef BOARD_maple diff --git a/wirish/boards/maple.cpp b/wirish/boards/maple.cpp index cebd222..ba2261b 100644 --- a/wirish/boards/maple.cpp +++ b/wirish/boards/maple.cpp @@ -44,51 +44,51 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ - {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D14/PB8 */ /* Little header */ - {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D20/PC5 */ /* External header */ - {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ - {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ - {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ - {GPIOC, NULL, 6, 0, ADCx}, /* D35/PC6 */ - {GPIOC, NULL, 7, 0, ADCx}, /* D36/PC7 */ - {GPIOC, NULL, 8, 0, ADCx}, /* D37/PC8 */ - {GPIOC, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, NULL, NULL, 6, 0, ADCx}, /* D35/PC6 */ + {GPIOC, NULL, NULL, 7, 0, ADCx}, /* D36/PC7 */ + {GPIOC, NULL, NULL, 8, 0, ADCx}, /* D37/PC8 */ + {GPIOC, NULL, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ }; #endif diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6.cpp index ae31ce3..962affc 100644 --- a/wirish/boards/maple_RET6.cpp +++ b/wirish/boards/maple_RET6.cpp @@ -38,51 +38,54 @@ void boardInit(void) { } stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { - {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ - {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + + /* Top header */ + + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D14/PB8 */ /* Little header */ - {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D20/PC5 */ /* External header */ - {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ - {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ - {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ - {GPIOC, TIMER8, 6, 1, ADCx}, /* D35/PC6 */ - {GPIOC, TIMER8, 7, 2, ADCx}, /* D36/PC7 */ - {GPIOC, TIMER8, 8, 3, ADCx}, /* D37/PC8 */ - {GPIOC, TIMER8, 9, 4, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D35/PC6 */ + {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D36/PC7 */ + {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D37/PC8 */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx} /* D38/PC9 (BUT) */ }; #endif diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp index 8c005cf..66a0997 100644 --- a/wirish/boards/maple_mini.cpp +++ b/wirish/boards/maple_mini.cpp @@ -45,43 +45,43 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOB, NULL, 11, 0, ADCx}, /* D0/PB11 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D1/PB10 */ - {GPIOB, NULL, 2, 0, ADCx}, /* D2/PB2 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D3/PB0 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D4/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D5/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D6/PA5 */ - {GPIOA, NULL, 4, 0, 4}, /* D7/PA4 */ - {GPIOA, TIMER2, 3, 4, 3}, /* D8/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D9/PA2 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D10/PA1 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D11/PA0 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D12/PC15 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D13/PC14 */ - {GPIOC, NULL, 13, 0, ADCx}, /* D14/PC13 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D0/PB11 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D1/PB10 */ + {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D2/PB2 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D3/PB0 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D4/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D5/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D6/PA5 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D7/PA4 */ + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D8/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D9/PA2 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D10/PA1 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D11/PA0 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D12/PC15 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D13/PC14 */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D14/PC13 */ /* Bottom header */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D15/PB7 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D16/PB6 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D17/PB5 */ - {GPIOB, NULL, 4, 0, ADCx}, /* D18/PB4 */ - {GPIOB, NULL, 3, 0, ADCx}, /* D19/PB3 */ - {GPIOA, NULL, 15, 0, ADCx}, /* D20/PA15 */ - {GPIOA, NULL, 14, 0, ADCx}, /* D21/PA14 */ - {GPIOA, NULL, 13, 0, ADCx}, /* D22/PA13 */ - {GPIOA, NULL, 12, 0, ADCx}, /* D23/PA12 */ - {GPIOA, TIMER1, 11, 4, ADCx}, /* D24/PA11 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D25/PA10 */ - {GPIOA, TIMER2, 9, 2, ADCx}, /* D26/PA9 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D27/PA8 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D28/PB15 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D29/PB14 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D30/PB13 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D32/PB8 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D33/PB1 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D15/PB7 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D16/PB6 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D17/PB5 */ + {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D18/PB4 */ + {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D19/PB3 */ + {GPIOA, NULL, NULL, 15, 0, ADCx}, /* D20/PA15 */ + {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D21/PA14 */ + {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D22/PA13 */ + {GPIOA, NULL, NULL, 12, 0, ADCx}, /* D23/PA12 */ + {GPIOA, TIMER1, NULL, 11, 4, ADCx}, /* D24/PA11 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D25/PA10 */ + {GPIOA, TIMER2, NULL, 9, 2, ADCx}, /* D26/PA9 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D27/PA8 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D28/PB15 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D29/PB14 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D30/PB13 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D32/PB8 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D33/PB1 */ }; #endif diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index c04e98f..75c6a2d 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -43,113 +43,113 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOB, NULL, 10, 0, ADCx}, /* D0/PB10 */ - {GPIOB, NULL, 2, 0, ADCx}, /* D1/PB2 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D2/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D3/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D4/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D5/PB15 */ - {GPIOC, NULL, 0, 0, 10}, /* D6/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D7/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D8/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D9/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D10/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D11/PC5 */ - {GPIOC, TIMER8, 6, 1, ADCx}, /* D12/PC6 */ - {GPIOC, TIMER8, 7, 2, ADCx}, /* D13/PC7 */ - {GPIOC, TIMER8, 8, 3, ADCx}, /* D14/PC8 */ - {GPIOC, TIMER8, 9, 4, ADCx}, /* D15/PC9 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D16/PC10 */ - {GPIOC, NULL, 11, 0, ADCx}, /* D17/PC11 */ - {GPIOC, NULL, 12, 0, ADCx}, /* D18/PC12 */ - {GPIOC, NULL, 13, 0, ADCx}, /* D19/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D20/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D21/PC15 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D22/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D23/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D24/PA10 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D25/PB9 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D0/PB10 */ + {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D1/PB2 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D2/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D3/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D4/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D5/PB15 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D6/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D7/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D8/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D9/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D10/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D11/PC5 */ + {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D12/PC6 */ + {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D13/PC7 */ + {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D14/PC8 */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx}, /* D15/PC9 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D16/PC10 */ + {GPIOC, NULL, NULL, 11, 0, ADCx}, /* D17/PC11 */ + {GPIOC, NULL, NULL, 12, 0, ADCx}, /* D18/PC12 */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D19/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D20/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D21/PC15 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D22/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D23/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D24/PA10 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D25/PB9 */ /* Bottom header */ - /* FIXME (?) What about D48--D50 also being TIMER2_CH[234]? */ + /* Note: D{48, 49, 50} are also TIMER2_CH{2, 3, 4}, respectively. */ - {GPIOD, NULL, 2, 0, ADCx}, /* D26/PD2 */ - {GPIOD, NULL, 3, 0, ADCx}, /* D27/PD3 */ - {GPIOD, NULL, 6, 0, ADCx}, /* D28/PD6 */ - {GPIOG, NULL, 11, 0, ADCx}, /* D29/PG11 */ - {GPIOG, NULL, 12, 0, ADCx}, /* D30/PG12 */ - {GPIOG, NULL, 13, 0, ADCx}, /* D31/PG13 */ - {GPIOG, NULL, 14, 0, ADCx}, /* D32/PG14 */ - {GPIOG, NULL, 8, 0, ADCx}, /* D33/PG8 */ - {GPIOG, NULL, 7, 0, ADCx}, /* D34/PG7 */ - {GPIOG, NULL, 6, 0, ADCx}, /* D35/PG6 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D36/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D37/PB6 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D38/PB7 */ - {GPIOF, NULL, 6, 0, 4}, /* D39/PF6 */ - {GPIOF, NULL, 7, 0, 5}, /* D40/PF7 */ - {GPIOF, NULL, 8, 0, 6}, /* D41/PF8 */ - {GPIOF, NULL, 9, 0, 7}, /* D42/PF9 */ - {GPIOF, NULL, 10, 0, 8}, /* D43/PF10 */ - {GPIOF, NULL, 11, 0, ADCx}, /* D44/PF11 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D45/PB1 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D46/PB0 */ - {GPIOA, TIMER5, 0, 1, 0}, /* D47/PA0 */ - {GPIOA, TIMER5, 1, 2, 1}, /* D48/PA1 */ - {GPIOA, TIMER5, 2, 3, 2}, /* D49/PA2 */ - {GPIOA, TIMER5, 3, 4, 3}, /* D50/PA3 */ - {GPIOA, NULL, 4, 0, 4}, /* D51/PA4 */ - {GPIOA, NULL, 5, 0, 5}, /* D52/PA5 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D53/PA6 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D54/PA7 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D26/PD2 */ + {GPIOD, NULL, NULL, 3, 0, ADCx}, /* D27/PD3 */ + {GPIOD, NULL, NULL, 6, 0, ADCx}, /* D28/PD6 */ + {GPIOG, NULL, NULL, 11, 0, ADCx}, /* D29/PG11 */ + {GPIOG, NULL, NULL, 12, 0, ADCx}, /* D30/PG12 */ + {GPIOG, NULL, NULL, 13, 0, ADCx}, /* D31/PG13 */ + {GPIOG, NULL, NULL, 14, 0, ADCx}, /* D32/PG14 */ + {GPIOG, NULL, NULL, 8, 0, ADCx}, /* D33/PG8 */ + {GPIOG, NULL, NULL, 7, 0, ADCx}, /* D34/PG7 */ + {GPIOG, NULL, NULL, 6, 0, ADCx}, /* D35/PG6 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D36/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D37/PB6 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D38/PB7 */ + {GPIOF, NULL, ADC3, 6, 0, 4}, /* D39/PF6 */ + {GPIOF, NULL, ADC3, 7, 0, 5}, /* D40/PF7 */ + {GPIOF, NULL, ADC3, 8, 0, 6}, /* D41/PF8 */ + {GPIOF, NULL, ADC3, 9, 0, 7}, /* D42/PF9 */ + {GPIOF, NULL, ADC3, 10, 0, 8}, /* D43/PF10 */ + {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D44/PF11 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D45/PB1 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D46/PB0 */ + {GPIOA, TIMER5, ADC1, 0, 1, 0}, /* D47/PA0 */ + {GPIOA, TIMER5, ADC1, 1, 2, 1}, /* D48/PA1 */ + {GPIOA, TIMER5, ADC1, 2, 3, 2}, /* D49/PA2 */ + {GPIOA, TIMER5, ADC1, 3, 4, 3}, /* D50/PA3 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D51/PA4 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D52/PA5 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D53/PA6 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D54/PA7 */ /* Right (triple) header */ - {GPIOF, NULL, 0, 0, ADCx}, /* D55/PF0 */ - {GPIOD, NULL, 11, 0, ADCx}, /* D56/PD11 */ - {GPIOD, NULL, 14, 0, ADCx}, /* D57/PD14 */ - {GPIOF, NULL, 1, 0, ADCx}, /* D58/PF1 */ - {GPIOD, NULL, 12, 0, ADCx}, /* D59/PD12 */ - {GPIOD, NULL, 15, 0, ADCx}, /* D60/PD15 */ - {GPIOF, NULL, 2, 0, ADCx}, /* D61/PF2 */ - {GPIOD, NULL, 13, 0, ADCx}, /* D62/PD13 */ - {GPIOD, NULL, 0, 0, ADCx}, /* D63/PD0 */ - {GPIOF, NULL, 3, 0, ADCx}, /* D64/PF3 */ - {GPIOE, NULL, 3, 0, ADCx}, /* D65/PE3 */ - {GPIOD, NULL, 1, 0, ADCx}, /* D66/PD1 */ - {GPIOF, NULL, 4, 0, ADCx}, /* D67/PF4 */ - {GPIOE, NULL, 4, 0, ADCx}, /* D68/PE4 */ - {GPIOE, NULL, 7, 0, ADCx}, /* D69/PE7 */ - {GPIOF, NULL, 5, 0, ADCx}, /* D70/PF5 */ - {GPIOE, NULL, 5, 0, ADCx}, /* D71/PE5 */ - {GPIOE, NULL, 8, 0, ADCx}, /* D72/PE8 */ - {GPIOF, NULL, 12, 0, ADCx}, /* D73/PF12 */ - {GPIOE, NULL, 6, 0, ADCx}, /* D74/PE6 */ - {GPIOE, NULL, 9, 0, ADCx}, /* D75/PE9 */ - {GPIOF, NULL, 13, 0, ADCx}, /* D76/PF13 */ - {GPIOE, NULL, 10, 0, ADCx}, /* D77/PE10 */ - {GPIOF, NULL, 14, 0, ADCx}, /* D78/PF14 */ - {GPIOG, NULL, 9, 0, ADCx}, /* D79/PG9 */ - {GPIOE, NULL, 11, 0, ADCx}, /* D80/PE11 */ - {GPIOF, NULL, 15, 0, ADCx}, /* D81/PF15 */ - {GPIOG, NULL, 10, 0, ADCx}, /* D82/PG10 */ - {GPIOE, NULL, 12, 0, ADCx}, /* D83/PE12 */ - {GPIOG, NULL, 0, 0, ADCx}, /* D84/PG0 */ - {GPIOD, NULL, 5, 0, ADCx}, /* D85/PD5 */ - {GPIOE, NULL, 13, 0, ADCx}, /* D86/PE13 */ - {GPIOG, NULL, 1, 0, ADCx}, /* D87/PG1 */ - {GPIOD, NULL, 4, 0, ADCx}, /* D88/PD4 */ - {GPIOE, NULL, 14, 0, ADCx}, /* D89/PE14 */ - {GPIOG, NULL, 2, 0, ADCx}, /* D90/PG2 */ - {GPIOE, NULL, 1, 0, ADCx}, /* D91/PE1 */ - {GPIOE, NULL, 15, 0, ADCx}, /* D92/PE15 */ - {GPIOG, NULL, 3, 0, ADCx}, /* D93/PG3 */ - {GPIOE, NULL, 0, 0, ADCx}, /* D94/PE0 */ - {GPIOD, NULL, 8, 0, ADCx}, /* D95/PD8 */ - {GPIOG, NULL, 4, 0, ADCx}, /* D96/PG4 */ - {GPIOD, NULL, 9, 0, ADCx}, /* D97/PD9 */ - {GPIOG, NULL, 5, 0, ADCx}, /* D98/PG5 */ - {GPIOD, NULL, 10, 0, ADCx} /* D99/PD10 */ + {GPIOF, NULL, NULL, 0, 0, ADCx}, /* D55/PF0 */ + {GPIOD, NULL, NULL, 11, 0, ADCx}, /* D56/PD11 */ + {GPIOD, NULL, NULL, 14, 0, ADCx}, /* D57/PD14 */ + {GPIOF, NULL, NULL, 1, 0, ADCx}, /* D58/PF1 */ + {GPIOD, NULL, NULL, 12, 0, ADCx}, /* D59/PD12 */ + {GPIOD, NULL, NULL, 15, 0, ADCx}, /* D60/PD15 */ + {GPIOF, NULL, NULL, 2, 0, ADCx}, /* D61/PF2 */ + {GPIOD, NULL, NULL, 13, 0, ADCx}, /* D62/PD13 */ + {GPIOD, NULL, NULL, 0, 0, ADCx}, /* D63/PD0 */ + {GPIOF, NULL, NULL, 3, 0, ADCx}, /* D64/PF3 */ + {GPIOE, NULL, NULL, 3, 0, ADCx}, /* D65/PE3 */ + {GPIOD, NULL, NULL, 1, 0, ADCx}, /* D66/PD1 */ + {GPIOF, NULL, NULL, 4, 0, ADCx}, /* D67/PF4 */ + {GPIOE, NULL, NULL, 4, 0, ADCx}, /* D68/PE4 */ + {GPIOE, NULL, NULL, 7, 0, ADCx}, /* D69/PE7 */ + {GPIOF, NULL, NULL, 5, 0, ADCx}, /* D70/PF5 */ + {GPIOE, NULL, NULL, 5, 0, ADCx}, /* D71/PE5 */ + {GPIOE, NULL, NULL, 8, 0, ADCx}, /* D72/PE8 */ + {GPIOF, NULL, NULL, 12, 0, ADCx}, /* D73/PF12 */ + {GPIOE, NULL, NULL, 6, 0, ADCx}, /* D74/PE6 */ + {GPIOE, NULL, NULL, 9, 0, ADCx}, /* D75/PE9 */ + {GPIOF, NULL, NULL, 13, 0, ADCx}, /* D76/PF13 */ + {GPIOE, NULL, NULL, 10, 0, ADCx}, /* D77/PE10 */ + {GPIOF, NULL, NULL, 14, 0, ADCx}, /* D78/PF14 */ + {GPIOG, NULL, NULL, 9, 0, ADCx}, /* D79/PG9 */ + {GPIOE, NULL, NULL, 11, 0, ADCx}, /* D80/PE11 */ + {GPIOF, NULL, NULL, 15, 0, ADCx}, /* D81/PF15 */ + {GPIOG, NULL, NULL, 10, 0, ADCx}, /* D82/PG10 */ + {GPIOE, NULL, NULL, 12, 0, ADCx}, /* D83/PE12 */ + {GPIOG, NULL, NULL, 0, 0, ADCx}, /* D84/PG0 */ + {GPIOD, NULL, NULL, 5, 0, ADCx}, /* D85/PD5 */ + {GPIOE, NULL, NULL, 13, 0, ADCx}, /* D86/PE13 */ + {GPIOG, NULL, NULL, 1, 0, ADCx}, /* D87/PG1 */ + {GPIOD, NULL, NULL, 4, 0, ADCx}, /* D88/PD4 */ + {GPIOE, NULL, NULL, 14, 0, ADCx}, /* D89/PE14 */ + {GPIOG, NULL, NULL, 2, 0, ADCx}, /* D90/PG2 */ + {GPIOE, NULL, NULL, 1, 0, ADCx}, /* D91/PE1 */ + {GPIOE, NULL, NULL, 15, 0, ADCx}, /* D92/PE15 */ + {GPIOG, NULL, NULL, 3, 0, ADCx}, /* D93/PG3 */ + {GPIOE, NULL, NULL, 0, 0, ADCx}, /* D94/PE0 */ + {GPIOD, NULL, NULL, 8, 0, ADCx}, /* D95/PD8 */ + {GPIOG, NULL, NULL, 4, 0, ADCx}, /* D96/PG4 */ + {GPIOD, NULL, NULL, 9, 0, ADCx}, /* D97/PD9 */ + {GPIOG, NULL, NULL, 5, 0, ADCx}, /* D98/PG5 */ + {GPIOD, NULL, NULL, 10, 0, ADCx} /* D99/PD10 */ }; #endif diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp index 060994f..f9ccd39 100644 --- a/wirish/ext_interrupts.cpp +++ b/wirish/ext_interrupts.cpp @@ -49,7 +49,7 @@ void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { exti_trigger_mode outMode = exti_out_mode(mode); - exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin), + exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit), gpio_exti_port(PIN_MAP[pin].gpio_device), handler, outMode); @@ -64,7 +64,7 @@ void detachInterrupt(uint8 pin) { return; } - exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin)); + exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit)); } static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) { diff --git a/wirish/io.h b/wirish/io.h index 8dad1d1..7d4fab1 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -28,8 +28,8 @@ * @brief Arduino-compatible digital pin I/O interface. */ -#ifndef _IO_H -#define _IO_H +#ifndef _IO_H_ +#define _IO_H_ #include "gpio.h" #include "adc.h" @@ -45,8 +45,8 @@ * This enum specifies the complete set of possible configurations; * not every pin can have all of these modes. For example, on the * Maple, pin 15 may be configured as INPUT_ANALOG, but not as PWM. - * See your device's silkscreen and and the GPIO documentation for - * more information. + * See your board's documentation and silkscreen for more information + * on what functionality is available on each pin. * * @see pinMode() */ @@ -114,8 +114,7 @@ typedef enum WiringPinMode { /** * Configure behavior of a GPIO pin. * - * @param pin Pin to configure. One of: 0-38 (pin numbers as labeled - * on silkscreen), or D0-D38 (symbols for same) + * @param pin Number of pin to configure. * @param mode Mode corresponding to desired pin behavior. * @see WiringPinMode */ @@ -136,8 +135,7 @@ void digitalWrite(uint8 pin, uint8 value); * Read a digital value from a pin. The pin must have its mode set to * one of INPUT, INPUT_PULLUP, and INPUT_PULLDOWN. * - * @param pin Pin to read from. One of: 0-38 (pin numbers as labeled - * on silkscreen), or D0-D38 (symbols for same) + * @param pin Pin to read from. * @return LOW or HIGH. * @see pinMode() */ @@ -146,18 +144,14 @@ uint32 digitalRead(uint8 pin); /** * Read an analog value from pin. This function blocks during ADC * conversion, and has 12 bits of resolution. The pin must have its - * mode set to INPUT_ANALOG. Ignoring function call overhead, - * conversion time is 55.5 cycles. + * mode set to INPUT_ANALOG. * - * @param pin Pin to read from. One of: 0, 1, 2, 3, 10, 11, 12, 13, - * 15, 16, 17, 18, 19, 20, 27, 28. - - * @return ADC-converted voltage, in the range 0--4095, inclusive - * (i.e. a 12-bit ADC conversion). - + * @param pin Pin to read from. + * @return Converted voltage, in the range 0--4095, (i.e. a 12-bit ADC + * conversion). * @see pinMode() */ -uint32 analogRead(uint8 pin); +uint16 analogRead(uint8 pin); /** * Toggles the digital value at the given pin. @@ -207,14 +201,15 @@ uint8 isButtonPressed(); * pinMode(BOARD_BUTTON_PIN, INPUT). * * @param timeout_millis Number of milliseconds to wait until the - * button is pressed. If timeout_millis is 0, wait forever. + * button is pressed. If timeout_millis is left out (or 0), wait + * forever. * * @return true, if the button was pressed; false, if the timeout was * reached. * * @see pinMode() */ -uint8 waitForButtonPress(uint32 timeout_millis); +uint8 waitForButtonPress(uint32 timeout_millis=0); /** * Shift out a byte of data, one bit at a time. diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp index 6b09cef..4c803d2 100644 --- a/wirish/pwm.cpp +++ b/wirish/pwm.cpp @@ -38,5 +38,5 @@ void pwmWrite(uint8 pin, uint16 duty_cycle) { return; } - timer_set_compare(dev, PIN_MAP[pin].timer_chan, duty_cycle); + timer_set_compare(dev, PIN_MAP[pin].timer_channel, duty_cycle); } diff --git a/wirish/rules.mk b/wirish/rules.mk index c1d59bc..7715068 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -16,6 +16,7 @@ cSRCS_$(d) := cppSRCS_$(d) := wirish_math.cpp \ Print.cpp \ + boards.cpp \ boards/maple.cpp \ boards/maple_mini.cpp \ boards/maple_native.cpp \ @@ -24,14 +25,13 @@ cppSRCS_$(d) := wirish_math.cpp \ comm/HardwareSPI.cpp \ usb_serial.cpp \ cxxabi-compat.cpp \ - wirish.cpp \ wirish_shift.cpp \ wirish_analog.cpp \ time.cpp \ pwm.cpp \ ext_interrupts.cpp \ wirish_digital.cpp \ - native_sram.cpp \ + native_sram.cpp cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%) diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp deleted file mode 100644 index aeed089..0000000 --- a/wirish/wirish.cpp +++ /dev/null @@ -1,128 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief Generic Maple board initialization. - * - * By default, we bring up all Maple boards to 72MHz, clocked off the - * PLL, driven by the 8MHz external crystal. AHB and APB2 are clocked - * at 72MHz. APB1 is clocked at 36MHz. - */ - -#include "wirish.h" - -#include "flash.h" -#include "rcc.h" -#include "nvic.h" -#include "systick.h" -#include "gpio.h" -#include "adc.h" -#include "timer.h" -#include "usb.h" - -static void setupFlash(void); -static void setupClocks(void); -static void setupADC(void); -static void setupTimers(void); - -/** - * Board-wide initialization function. Called before main(). - */ -void init(void) { - setupFlash(); - setupClocks(); - nvic_init(); - systick_init(SYSTICK_RELOAD_VAL); - gpio_init_all(); - afio_init(); - setupADC(); - setupTimers(); - setupUSB(); - boardInit(); -} - -static void setupFlash(void) { - flash_enable_prefetch(); - flash_set_latency(FLASH_WAIT_STATE_2); -} - -/* - * Clock setup. Note that some of this only takes effect if we're - * running bare metal and the bootloader hasn't done it for us - * already. - * - * If you change this function, you MUST change the file-level Doxygen - * comment above. - */ -static void setupClocks() { - rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9); - rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1); - rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2); - rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); -} - -/* TODO initialize more ADCs on high density boards. */ -static void setupADC() { - adc_init(ADC1, 0); - adc_set_sample_rate(ADC1, ADC_SMPR_55_5); // for high impedance inputs -} - -static void timerDefaultConfig(timer_dev*); - -static void setupTimers() { - timer_foreach(timerDefaultConfig); -} - -static void timerDefaultConfig(timer_dev *dev) { - timer_adv_reg_map *regs = (dev->regs).adv; - const uint16 full_overflow = 0xFFFF; - const uint16 half_duty = 0x8FFF; - - timer_init(dev); - timer_pause(dev); - - regs->CR1 = TIMER_CR1_ARPE; - regs->PSC = 1; - regs->SR = 0; - regs->DIER = 0; - regs->EGR = TIMER_EGR_UG; - - switch (dev->type) { - case TIMER_ADVANCED: - regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; - // fall-through - case TIMER_GENERAL: - timer_set_reload(dev, full_overflow); - - for (int channel = 1; channel <= 4; channel++) { - timer_set_compare(dev, channel, half_duty); - timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, TIMER_OC_PE); - } - // fall-through - case TIMER_BASIC: - break; - } - - timer_resume(dev); -} diff --git a/wirish/wirish.h b/wirish/wirish.h index 13b14b6..880157d 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -67,7 +67,5 @@ typedef uint8 boolean; typedef uint8 byte; -void init(void); - #endif diff --git a/wirish/wirish_analog.cpp b/wirish/wirish_analog.cpp index 9e99aa5..8756caf 100644 --- a/wirish/wirish_analog.cpp +++ b/wirish/wirish_analog.cpp @@ -31,11 +31,12 @@ #include "io.h" /* Assumes that the ADC has been initialized and that the pin is set - * to ANALOG_INPUT */ -uint32 analogRead(uint8 pin) { - if(PIN_MAP[pin].adc_channel == ADCx) { + * to INPUT_ANALOG */ +uint16 analogRead(uint8 pin) { + const adc_dev *dev = PIN_MAP[pin].adc_device; + if (dev == NULL) { return 0; } - return adc_read(ADC1, PIN_MAP[pin].adc_channel); + return adc_read(dev, PIN_MAP[pin].adc_channel); } diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp index 278cf10..115e91e 100644 --- a/wirish/wirish_digital.cpp +++ b/wirish/wirish_digital.cpp @@ -70,20 +70,14 @@ void pinMode(uint8 pin, WiringPinMode mode) { return; } - gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, outputMode); + gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, outputMode); if (PIN_MAP[pin].timer_device != NULL) { - /* enable/disable timer channels if we're switching into or - out of pwm */ - if (pwm) { - timer_set_mode(PIN_MAP[pin].timer_device, - PIN_MAP[pin].timer_chan, - TIMER_PWM); - } else { - timer_set_mode(PIN_MAP[pin].timer_device, - PIN_MAP[pin].timer_chan, - TIMER_DISABLED); - } + /* Enable/disable timer channels if we're switching into or + * out of PWM. */ + timer_set_mode(PIN_MAP[pin].timer_device, + PIN_MAP[pin].timer_channel, + pwm ? TIMER_PWM : TIMER_DISABLED); } } @@ -93,7 +87,7 @@ uint32 digitalRead(uint8 pin) { return 0; } - return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin) ? + return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit) ? HIGH : LOW; } @@ -102,7 +96,7 @@ void digitalWrite(uint8 pin, uint8 val) { return; } - gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, val); + gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, val); } void togglePin(uint8 pin) { @@ -110,12 +104,14 @@ void togglePin(uint8 pin) { return; } - gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin); + gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit); } +#define BUTTON_DEBOUNCE_DELAY 10 + uint8 isButtonPressed() { if (digitalRead(BOARD_BUTTON_PIN)) { - delay(1); + delay(BUTTON_DEBOUNCE_DELAY); while (digitalRead(BOARD_BUTTON_PIN)) ; return true; diff --git a/wirish/wirish_types.h b/wirish/wirish_types.h index 84591ea..7d6e31a 100644 --- a/wirish/wirish_types.h +++ b/wirish/wirish_types.h @@ -32,20 +32,28 @@ #include "gpio.h" #include "timer.h" +#include "adc.h" #ifndef _WIRISH_TYPES_H_ #define _WIRISH_TYPES_H_ -/** Stores STM32-specific information related to a given pin. */ +/** + * Invalid stm32_pin_info adc_channel value. + * @see stm32_pin_info + */ +#define ADCx 0xFF + +/** + * @brief Stores STM32-specific information related to a given Maple pin. + * @see PIN_MAP + */ typedef struct stm32_pin_info { - gpio_dev *gpio_device; /**< Maple pin's GPIO device */ - timer_dev *timer_device; /**< Maple pin's timer device, or NULL if none. */ - uint8 gpio_pin; /**< GPIO pin */ - uint8 timer_chan; /**< Timer channel, or 0 if none. */ - uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ + gpio_dev *gpio_device; /**< Maple pin's GPIO device */ + timer_dev *timer_device; /**< Pin's timer device, if any. */ + const adc_dev *adc_device; /**< ADC device, if any. */ + uint8 gpio_bit; /**< Pin's GPIO port bit. */ + uint8 timer_channel; /**< Timer channel, or 0 if none. */ + uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ } stm32_pin_info; -/** Invalid adc_channel value */ -#define ADCx 0xFF - #endif -- cgit v1.2.3 From 09de1019a60125f3f5932a21377670d3cb030121 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 30 Mar 2011 03:44:57 -0400 Subject: Nitpicks --- libmaple/scb.h | 4 ++++ wirish/io.h | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) (limited to 'wirish') diff --git a/libmaple/scb.h b/libmaple/scb.h index f851a08..8bfdda3 100644 --- a/libmaple/scb.h +++ b/libmaple/scb.h @@ -29,6 +29,8 @@ #ifndef _SCB_H_ #define _SCB_H_ +/* FIXME this definition is missing doxygen comments */ + typedef struct scb_reg_map { __io uint32 CPUID; // CPU ID Base Register __io uint32 ICSR; // Interrupt Control State Register @@ -51,6 +53,8 @@ typedef struct scb_reg_map { __io uint32 ISAR[5]; // ISA Feature Register } scb_reg_map; +/* FIXME these names violate the libmaple naming conventions */ + #define SCB_BASE 0xE000ED00 #define SCB ((scb_reg_map*)(SCB_BASE)) diff --git a/wirish/io.h b/wirish/io.h index 7d4fab1..0ffbd10 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -223,7 +223,7 @@ uint8 waitForButtonPress(uint32 timeout_millis=0); * @param dataPin Pin to shift data out on * @param clockPin Pin to pulse after each bit is shifted out * @param bitOrder Either MSBFIRST (big-endian) or LSBFIRST (little-endian). - * @param val Value to shift out + * @param value Value to shift out */ void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 value); -- cgit v1.2.3 From efbc87c64d89bbb367b6d8face6c50edf0eb5e5c Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 30 Mar 2011 05:58:58 -0400 Subject: Removed Maple-specific information from digitalWrite() doxygen comment. --- wirish/io.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) (limited to 'wirish') diff --git a/wirish/io.h b/wirish/io.h index 0ffbd10..4e415b5 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -122,10 +122,9 @@ void pinMode(uint8 pin, WiringPinMode mode); /** * Writes a (digital) value to a pin. The pin must have its - * mode set to OUTPUT or OUTPUT_OPEN_DRAIN. + * mode set to OUTPUT or OUTPUT_OPEN_DRAIN. * - * @param pin Pin to write to. One of: 0-38 (pin numbers as labeled - * on silkscreen), or D0-D38 (symbols for same) + * @param pin Pin to write to. * @param value Either LOW (write a 0) or HIGH (write a 1). * @see pinMode() */ -- cgit v1.2.3 From b13926073f47012d6654b0236f195c4356831fc2 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 30 Mar 2011 00:55:51 -0400 Subject: Board-specific values; corresponding QA test generalizations. Various board-specific #defines and arrays of pins added. For the changelog (some of this information predates this commit): * wirish/boards.h now declares the following arrays of pin numbers: * boardPWMPins - PWM-capable pins * boardADCPins - ADC-capable pins * boardUsedPins - pins already in use, e.g. BOARD_BUTTON_PIN It also declares a bool boardUsesPin(uint8 pin) function for convenient testing of whether a pin is in use. * wirish/boards/*.h now define: * BOARD_USART1_TX_PIN * BOARD_USART1_RX_PIN * BOARD_USART2_TX_PIN * BOARD_USART2_RX_PIN * BOARD_USART3_TX_PIN * BOARD_USART3_RX_PIN * BOARD_NR_GPIO_PINS (renamed from NR_GPIO_PINS) * BOARD_NR_USARTS (renamed from NR_USARTS) * BOARD_NR_PWM_PINS * BOARD_NR_ADC_PINS * BOARD_NR_USED_PINS * wirish/boards/maple_native.h now defines: * BOARD_UART4_TX_PIN * BOARD_UART4_RX_PIN * BOARD_UART5_TX_PIN * BOARD_UART5_RX_PIN (Unfortunately, wirish/boards/maple_RET6.h cannot, since at least one of the UART4/UART5 pins are used already; this will require layout changes for a wide-release Maple form factor RET6 board). * wirish/boards/*.cpp all include the corresponding array definitions. They all live in flash by default, thanks to the new __FLASH__ macro in wirish/wirish_types.h, which is a synonym for the existing __attr_flash #define in libmaple/libmaple_types.h. The documentation was updated to include this information. It also gained various FIXME/TODO comments related to its generalization across boards. The quality assurance-related examples (examples/qa-slave-shield.cpp and examples/test-session.cpp) now make heavy use of board-specific values to ensure portability. --- docs/source/arm-gcc.rst | 53 +- docs/source/compatibility.rst | 2 + docs/source/gpio.rst | 2 + docs/source/i2c.rst | 19 +- docs/source/index.rst | 1 + docs/source/lang/api/analogread.rst | 33 +- docs/source/lang/api/board-values.rst | 155 +++++ docs/source/lang/api/boardusespin.rst | 27 + docs/source/lang/api/constants.rst | 26 +- docs/source/lang/api/hardwaretimer.rst | 6 + docs/source/lang/api/isbuttonpressed.rst | 5 +- docs/source/lang/api/pwmwrite.rst | 2 + docs/source/lang/api/toggleled.rst | 2 +- docs/source/lang/api/waitforbuttonpress.rst | 2 + docs/source/language-index.rst | 4 +- docs/source/language.rst | 46 +- docs/source/libmaple.rst | 12 +- examples/qa-slave-shield.cpp | 48 +- examples/test-session.cpp | 847 ++++++++++++++++------------ wirish/boards.cpp | 22 +- wirish/boards.h | 43 +- wirish/boards/maple.cpp | 14 +- wirish/boards/maple.h | 16 +- wirish/boards/maple_RET6.cpp | 14 +- wirish/boards/maple_RET6.h | 8 +- wirish/boards/maple_mini.cpp | 17 +- wirish/boards/maple_mini.h | 8 +- wirish/boards/maple_native.cpp | 16 +- wirish/boards/maple_native.h | 15 +- wirish/comm/HardwareSerial.cpp | 4 +- wirish/ext_interrupts.cpp | 4 +- wirish/pwm.cpp | 2 +- wirish/wirish_digital.cpp | 10 +- wirish/wirish_types.h | 3 + 34 files changed, 985 insertions(+), 503 deletions(-) create mode 100644 docs/source/lang/api/board-values.rst create mode 100644 docs/source/lang/api/boardusespin.rst (limited to 'wirish') diff --git a/docs/source/arm-gcc.rst b/docs/source/arm-gcc.rst index ef745f5..7ecb5d4 100644 --- a/docs/source/arm-gcc.rst +++ b/docs/source/arm-gcc.rst @@ -4,12 +4,11 @@ GCC for Maple ============= -This document provides notes on the current usage of -``arm-none-eabi-gcc``, the `CodeSourcery `_ -version of the GNU `GCC `_ compilers used to -compile programs for the Maple. It is not intended as a reference -manual for GCC; such manuals are available `elsewhere -`_. +This document provides notes on using of ``arm-none-eabi-gcc``, the +`CodeSourcery `_ version of the GNU `GCC +`_ compilers used for the Maple boards. It is +not intended as a reference manual for GCC; such manuals are available +`elsewhere `_. Obtaining ``arm-none-eabi-gcc`` ------------------------------- @@ -17,21 +16,24 @@ Obtaining ``arm-none-eabi-gcc`` Recent versions of ``arm-none-eabi-gcc`` and associated tools are included with the :ref:`Maple IDE `. -Users who wish to use ``arm-none-eabi-gcc`` in concert with a standard -Unix toolchain are referred to our :ref:`unix-toolchain` reference, -which describes how to set up such an environment. +Users who wish to use ``arm-none-eabi-gcc`` directly, along with a +standard Unix Make-based toolchain, should read the +:ref:`unix-toolchain`, which describes how to set up such an +environment. -LeafLabs mirrors some of the more recent versions of the compiler -under http://static.leaflabs.com/pub/codesourcery/\ , including -versions for OS X, win32, and 32-bit Linux. +LeafLabs maintains `mirrors +`_ for some of the more +recent versions of the compiler, including versions for OS X, Win32, +and 32-bit Linux. Compiler Flags Used by libmaple ------------------------------- This section documents the flags passed to ``arm-none-eabi-gcc`` by -the :ref:`Maple IDE ` and the default Makefile provided with -:ref:`libmaple `. The information in this section is -subject to change without notice. +the :ref:`Maple IDE ` and the default Makefile provided with the +:ref:`Unix toolchain `. The information in this +section is subject to change between :ref:`libmaple ` +releases. .. highlight:: sh @@ -40,7 +42,8 @@ The following flags are among those passed to the C compiler:: -Os -g -mcpu=cortex-m3 -mthumb -march=armv7-m -nostdlib -ffunction-sections -fdata-sections -Wl,--gc-sections -The following flags are among those passed to the C++ compiler:: +In addition to those flags just given for the C compiler, the +following flags are among those passed to the C++ compiler:: -fno-rtti -fno-exceptions -Wall @@ -52,6 +55,15 @@ The following flags are among those passed to the assembler:: .. _arm-gcc-avr-gcc: +Using the C Standard Library +---------------------------- + +By default (under both the :ref:`Maple IDE ` and the :ref:`Unix +toolchain `), ``arm-none-eabi-gcc`` is configured to +link against `newlib `_, a C standard +library intended for use with embedded applications. You are free to +include of any of its headers. + Switching from AVR-GCC ---------------------- @@ -63,8 +75,11 @@ including Arduino) for use on the Maple. .. _arm-gcc-attribute-flash: - Replacing ``PROGMEM``: You can direct the linker script provided - with libmaple to store a variable in flash by using - ``__attribute__((section (".USER_FLASH")))``, like so:: + with libmaple to store a variable in Flash (instead of RAM) by using + the libmaple macro ``__FLASH__``, like so:: - uint32 arr[] __attribute__((section (".USER_FLASH"))) = {...}; + uint32 array[] __FLASH__ = {0, 1, 2}; + Be aware, however, that if you do that, you can only store values + which are compile-time constants, and that if you attempt to change + a variable stored in Flash, your program will crash. diff --git a/docs/source/compatibility.rst b/docs/source/compatibility.rst index 0d6319f..eb28ad2 100644 --- a/docs/source/compatibility.rst +++ b/docs/source/compatibility.rst @@ -41,6 +41,8 @@ means that programs aren't much larger (or are even smaller). Header Numbering and Incompatibilities -------------------------------------- +.. FIXME generalize Maple-specific information + The numbering of headers is different; on the Maple each GPIO has a unique number: D0, D1, D2, all the way up to D37 (actually, there are :ref:`a few more `...). On the Arduino, the analog pins are diff --git a/docs/source/gpio.rst b/docs/source/gpio.rst index cebb402..5daf43c 100644 --- a/docs/source/gpio.rst +++ b/docs/source/gpio.rst @@ -3,6 +3,8 @@ GPIO ==== +.. FIXME generalize this maple-specific information + The Maple features 38 ready-to-use general purpose input/output (GPIO) pins for digital input/output, numbered D0 through D37. These numbers correspond to the numeric values next to each header on the Maple diff --git a/docs/source/i2c.rst b/docs/source/i2c.rst index b4a996b..e2a7a04 100644 --- a/docs/source/i2c.rst +++ b/docs/source/i2c.rst @@ -4,11 +4,16 @@ |i2c| ===== +.. FIXME update this documentation once you write the Wire library on +.. top of libmaple i2c. + +.. FIXME generalize Maple-specific documentation + .. note:: - The |i2c| interface is currently only available from the 'i2c' branch - of the github `libmaple `_ - repository. + The |i2c| interface is currently only available from the 'refactor' + branch of the github `libmaple + `_ repository. |i2c| is a crude and easy-to-hack serial protocol that requires only two wires/channels for communication between many devices. Every @@ -56,10 +61,8 @@ Function Reference ------------------ The function API for |i2c| is not finished! See the `source code -`_ for -now. - -.. TODO link to libmaple I2C docs once (1) finished, (2) in master +`_ +for now. SMBus ----- @@ -68,8 +71,6 @@ The STM32 microcontroller has hardware support for SMBus; we simply have not written software for it. The SMBAL line for i2c1 is on header D4 and for i2c2 is on D31. -.. TODO link to libmaple SMBus docs once (1) finished, (2) in master - .. _i2c-recommended-reading: Recommended Reading diff --git a/docs/source/index.rst b/docs/source/index.rst index 4369fbd..de71411 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -38,6 +38,7 @@ Have fun! Bootloader Troubleshooting Known Problems + Notes on GCC's ARM target .. _index-hardware: diff --git a/docs/source/lang/api/analogread.rst b/docs/source/lang/api/analogread.rst index 35c6fbc..7099b69 100644 --- a/docs/source/lang/api/analogread.rst +++ b/docs/source/lang/api/analogread.rst @@ -35,6 +35,8 @@ have to do this once, so it's usually done in :ref:`lang-setup`\ ). Parameter Discussion -------------------- +.. FIXME generalize Maple-specific information + The pin parameter is the number of the analog input pin to read from. Header pins on the Maple with ADC functionality (marked as "AIN" on the silkscreen) are: @@ -49,24 +51,25 @@ Note ---- If the analog input pin is not connected to anything, the value -returned by analogRead() will fluctuate based on a number of factors -(e.g. the values of the other analog inputs, how close your hand is to -the board, etc.) in a seemingly random way. +returned by ``analogRead()`` will fluctuate due to a number of reasons +(like the values of the other analog inputs, how close your hand is to +the board, etc.) in a "random" way. Example ------- - :: +:: + int analogPin = 3; // Potentiometer wiper (middle terminal) connected + // to analog pin 3. outside leads to ground and +3.3V. + // You may have to change this value if your board + // cannot perform ADC conversion on pin 3. - int analogPin = 3; // potentiometer wiper (middle terminal) connected - // to analog pin 3. outside leads to ground and +3.3V int val = 0; // variable to store the value read void setup() { pinMode(analogPin, INPUT_ANALOG); // set up pin for analog input - SerialUSB.begin(); // set up usb virtual COM port } void loop() { @@ -97,23 +100,27 @@ shift ` the value of a Maple readout by 2, like so:: // be aware that you're losing a lot of precision if you do this int adc_reading = analogRead(pin) >> 2; +.. FIXME Mention Native can do analogReference(), when it's time + On the Arduino, the input range and resolution can be changed using their implementation of `analogReference() `_\ . Because of the way its hardware (as of Rev 5) was designed, it's not possible to implement analogReference on the Maple, so this function doesn't exist. If your inputs lie in a different voltage range than 0V--3.3V, -you'll need to bring them into that range before using analogRead. -Some basic tools to accomplish this are `resistor dividers -`_ and `Zener diodes +you'll need to bring them into that range before using +``analogRead()``. Some basic tools to accomplish this are `resistor +dividers `_ and `Zener +diodes `_\ -. However, opamps and other powered components can also be used if -greater precision is required. +. However, `operational amplifiers +`_ and other +powered components can also be used if greater precision is required. See also -------- -- :ref:`ADC note ` +- :ref:`ADC tutorial ` - `(Arduino) Tutorial: Analog Input Pins `_ .. include:: cc-attribution.txt diff --git a/docs/source/lang/api/board-values.rst b/docs/source/lang/api/board-values.rst new file mode 100644 index 0000000..367adbb --- /dev/null +++ b/docs/source/lang/api/board-values.rst @@ -0,0 +1,155 @@ +.. _lang-board-values: + +Board-Specific Constants +======================== + +There are a number of board-specific values: constants or variables +which are different depending on which LeafLabs board you have. + +This page lists and documents the board-specific values. You should +use these when appropriate in your own programs. This will help make +it easier to share your code with other people who have different +boards. Some example usages are given :ref:`below +`. + +.. contents:: Contents + :local: + +Constants +--------- + +- ``CYCLES_PER_MICROSECOND``: Number of CPU cycles per microsecond on + your board. + +.. _lang-board-values-but: + +- ``BOARD_BUTTON_PIN``: Pin connected to the built-in button (labeled + "BUT" on your board's silkscreen). + +.. _lang-board-values-led: + +- ``BOARD_LED_PIN``: Pin connected to the built-in LED. + +- ``BOARD_NR_GPIO_PINS``: Total number of :ref:`GPIO pins ` that + are broken out to headers. Some of these might already be connected + to external hardware (like the built-in LED and button). To find + out if a pin is in use, see :ref:`boardUsesPin() + ` (and also :ref:`boardUsedPins + `). + +.. _lang-board-values-nr-pwm-pins: + +- ``BOARD_NR_PWM_PINS``: Total *number* of GPIO pins that can be used + for :ref:`PWM `. The actual *pins* that can do PWM are in the + :ref:`boardPWMPins ` array. + +.. _lang-board-values-nr-adc-pins: + +- ``BOARD_NR_ADC_PINS``: Total number of GPIO pins that can be used + for :ref:`analog-to-digital conversion `. The actual pins that + can do ADC conversion are in the :ref:`boardADCPins + ` array. + +.. _lang-board-values-nr-used-pins: + +- ``BOARD_NR_USED_PINS``: Total number of GPIO pins that are already + connected to some external hardware (like a built-in LED) on the + board. The actual pins that that are already used are in the + :ref:`boardUsedPins ` array. To see if + a pin is already in use, use the :ref:`boardUsesPin() + ` function. + +.. _lang-board-values-usart: + +- USART (serial port) related constants: + + * ``BOARD_USART1_TX_PIN``, ``BOARD_USART2_TX_PIN``, ``BOARD_USART3_TX_PIN``: + TX pins for the 3 USARTS. + + * ``BOARD_USART1_RX_PIN``, ``BOARD_USART2_RX_PIN``, ``BOARD_USART3_RX_PIN``: + RX pins for the 3 USARTS. + + * ``BOARD_UART4_TX_PIN``, ``BOARD_UART5_TX_PIN``: TX pins for + UARTs 4 and 5 (high-density boards like Maple Native only). + + * ``BOARD_UART4_RX_PIN``, ``BOARD_UART5_RX_PIN``: RX pins for + UARTs 4 and 5 (high-density boards like Maple Native only). + + * ``BOARD_NR_USARTS``: Number of serial ports on the board. This + number includes UARTs 4 and 5 if they are available. + +.. _lang-board-values-pwm-pins: +.. _lang-board-values-adc-pins: +.. _lang-board-values-used-pins: + +Pin Arrays +---------- + +Some :ref:`arrays ` of pin numbers are available which you +can use to find out certain important information about a given pin. + +.. TODO add links to the board-specific hardware information on what +.. are in these arrays + +- ``boardPWMPins``: Pin numbers of each pin capable of :ref:`PWM + ` output, using :ref:`pwmWrite() `. The total + number of these pins is :ref:`BOARD_NR_PWM_PINS + `. + +- ``boardADCPins``: Pin numbers of each pin capable of :ref:`ADC + ` conversion, using :ref:`analogRead() `. The + total number of these pins is :ref:`BOARD_NR_ADC_PINS + `. + +- ``boardUsedPins``: Pin numbers of each pin that, by default, is used + for some special purpose by the board. The total number of these + pins is :ref:`BOARD_NR_USED_PINS `. + To check if a pin is used for a special purpose, use + :ref:`boardUsesPin() `. + +.. _lang-board-values-examples: + +Examples +-------- + +:ref:`BOARD_LED_PIN ` On the Maple, the +built-in LED is connected to pin 13. On the Maple Mini, however, it +is connected to pin 33. You can write a "blinky" program that works +on all LeafLabs boards using ``BOARD_LED_PIN`` and :ref:`toggleLED() +`:: + + void setup() { + pinMode(BOARD_LED_PIN, OUTPUT); + } + + void loop() { + toggleLED(); + delay(100); + } + +:ref:`BOARD_BUTTON_PIN `: Similarly, you can +write a single program that prints a message whenever the button is +pressed which will work on all LeafLabs boards using +``BOARD_BUTTON_PIN`` and :ref:`isButtonPressed() +`:: + + void setup() { + pinMode(BOARD_BUTTON_PIN, INPUT); + } + + void loop() { + if (isButtonPressed()) { + SerialUSB.println("You pressed the button!"); + } + } + +See Also +-------- + +- :ref:`lang-boardusespin` +- :ref:`lang-isbuttonpressed` +- :ref:`lang-waitforbuttonpress` +- :ref:`lang-pinmode` +- :ref:`lang-toggleled` +- :ref:`lang-analogread` +- :ref:`lang-pwmwrite` diff --git a/docs/source/lang/api/boardusespin.rst b/docs/source/lang/api/boardusespin.rst new file mode 100644 index 0000000..8dc4c64 --- /dev/null +++ b/docs/source/lang/api/boardusespin.rst @@ -0,0 +1,27 @@ +.. highlight:: cpp + +.. _lang-boardusespin: + +boardUsesPin() +============== + +Each LeafLabs board connects some pins to external hardware. The most +important examples of this are the built-in LED and button. You can +check if a board uses a particular pin using this function. + +Library Documentation +--------------------- + +.. doxygenfunction:: boardUsesPin + +See Also +-------- + +- :ref:`Board-specific values ` +- :ref:`boardUsedPins ` +- :ref:`BOARD_LED_PIN ` +- :ref:`toggleLED() ` +- :ref:`BOARD_BUTTON_PIN ` +- :ref:`isButtonPressed() ` +- :ref:`waitForButtonPress() ` + diff --git a/docs/source/lang/api/constants.rst b/docs/source/lang/api/constants.rst index 2e968e7..c5a7c0c 100644 --- a/docs/source/lang/api/constants.rst +++ b/docs/source/lang/api/constants.rst @@ -293,23 +293,16 @@ exponent indicators. Some examples are given in the following table: Board-Specific Constants ------------------------ -This section documents constants whose value might change across -different LeafLabs boards. You can use these constants to help ensure -that your code will be portable across different boards. +There are several :ref:`board-specific constants ` +whose value depends on which LeafLabs board you have. If you use +them, it will help make sure that your code will work well on all +LeafLabs boards, not just the one you have. This will make it much +easier to share your code with others. -.. TODO replace "upcoming" when Mini, Native come out - -.. _lang-constants-led: - -- ``BOARD_LED_PIN``: the number of the pin which connects to the - built-in LED. On the Maple, this is pin 13, but it's not guaranteed - to be the same in upcoming boards like the Maple Mini. - -.. _lang-constants-but: - -- ``BOARD_BUTTON_PIN``: the number of the pin which connects to the - built-in button (labeled "BUT"). On the Maple, this is pin 38, but - it's not guaranteed to be the same in other boards. +For example, the pin number connected to the board's built-in LED is +different on the different boards, but the board-specific constant +:ref:`BOARD_LED_PIN ` will always be the +correct value for each board. See Also -------- @@ -325,5 +318,6 @@ See Also - :ref:`unsigned long long ` - :ref:`float ` - :ref:`double ` +- :ref:`Board-Specific Values ` .. include:: cc-attribution.txt diff --git a/docs/source/lang/api/hardwaretimer.rst b/docs/source/lang/api/hardwaretimer.rst index c7a630d..3f086ca 100644 --- a/docs/source/lang/api/hardwaretimer.rst +++ b/docs/source/lang/api/hardwaretimer.rst @@ -10,6 +10,12 @@ built-in timer peripherals. More information on these peripherals (including code examples) is available in the :ref:`timers reference `. +.. FIXME update HardwareTimer documentation after redoing it in terms +.. of the new timer interface. + +.. warning:: This class has been deprecated. It is not available in + the current build. + Library Documentation --------------------- diff --git a/docs/source/lang/api/isbuttonpressed.rst b/docs/source/lang/api/isbuttonpressed.rst index dbff0c9..8c350b9 100644 --- a/docs/source/lang/api/isbuttonpressed.rst +++ b/docs/source/lang/api/isbuttonpressed.rst @@ -4,7 +4,8 @@ isButtonPressed() ================= Check whether the board's built-in button (labeled BUT on the -silkscreen) is pressed. +silkscreen) is pressed. The pin number of the built-in button is +given by the constant ``BOARD_BUTTON_PIN``. Library Documentation --------------------- @@ -14,4 +15,6 @@ Library Documentation See Also -------- +- :ref:`Board-specific values ` +- :ref:`BOARD_BUTTON_PIN ` - :ref:`lang-waitforbuttonpress` diff --git a/docs/source/lang/api/pwmwrite.rst b/docs/source/lang/api/pwmwrite.rst index 9d50077..cea602b 100644 --- a/docs/source/lang/api/pwmwrite.rst +++ b/docs/source/lang/api/pwmwrite.rst @@ -11,6 +11,8 @@ pwmWrite(), the pin will output a steady square wave with the given duty cycle. You can change the duty cycle later by calling pwmWrite() again with the same pin and a different duty. +.. FIXME board-specific information + On the Maple, the pins which support PWM are: 0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 27, and 28. diff --git a/docs/source/lang/api/toggleled.rst b/docs/source/lang/api/toggleled.rst index 0cc20c2..54a7d64 100644 --- a/docs/source/lang/api/toggleled.rst +++ b/docs/source/lang/api/toggleled.rst @@ -13,5 +13,5 @@ Library Documentation See Also -------- -- :ref:`BOARD_LED_PIN ` +- :ref:`BOARD_LED_PIN ` - :ref:`togglePin() ` diff --git a/docs/source/lang/api/waitforbuttonpress.rst b/docs/source/lang/api/waitforbuttonpress.rst index 34c5066..a5bd45c 100644 --- a/docs/source/lang/api/waitforbuttonpress.rst +++ b/docs/source/lang/api/waitforbuttonpress.rst @@ -14,4 +14,6 @@ Library Documentation See Also -------- +- :ref:`Board-specific values ` +- :ref:`BOARD_BUTTON_PIN ` - :ref:`lang-isbuttonpressed` diff --git a/docs/source/language-index.rst b/docs/source/language-index.rst index c949988..531e72c 100644 --- a/docs/source/language-index.rst +++ b/docs/source/language-index.rst @@ -26,13 +26,13 @@ programmers familiar with the Arduino language. | | | +----------------------------------+------------------------------------+ -.. Unimplemented in libmaple or not part of current release: +.. Unimplemented or not part of current release: .. toctree:: :hidden: + lang/unimplemented/tone.rst lang/unimplemented/notone.rst lang/unimplemented/pulsein.rst lang/unimplemented/stringclass.rst lang/unimplemented/stringobject.rst - lang/unimplemented/tone.rst diff --git a/docs/source/language.rst b/docs/source/language.rst index d340aec..ea841f5 100644 --- a/docs/source/language.rst +++ b/docs/source/language.rst @@ -10,6 +10,9 @@ The Maple can be programmed in the `Wiring `_ language, which is the same language used to program the `Arduino `_ boards. +.. TODO Wiring tutorial -- just describe setup()/loop(), then link to +.. some of the the bajillion external tutorials + C or C++ programmers curious about the differences between the Wiring language and C++ may wish to skip to the :ref:`arduino_c_for_c_hackers`. @@ -25,6 +28,21 @@ Maple Language Reference The following table summarizes the available core language features. A more exhaustive index is available at the :ref:`language-index`. +**Looking for something else?** + +- See the :ref:`libraries` for extra built-in libraries for dealing + with different kinds of hardware. + +.. FIXME mention Maple Native supports malloc(), free(), operator +.. new(), and operator delete(), when that is a true thing to say. + +- If you're looking for something from the C standard library (like + ``atoi()``, for instance): the :ref:`CodeSourcery GCC compiler + ` used to compile your programs is configured to link + against `newlib `_, and allows the + use of any of its header files. However, dynamic memory allocation + (``malloc()``, etc.) is not available. + +--------------------------------------------+----------------------------------------------+---------------------------------------------------+ | Structure | Variables | Functions | | | | | @@ -40,13 +58,13 @@ A more exhaustive index is available at the :ref:`language-index`. | |* :ref:`true ` | |* :ref:`togglePin() ` | |* :ref:`for ` | :ref:`false ` | | | | |* :ref:`toggleLED() ` | -|* :ref:`switch/case ` |* :ref:`BOARD_LED_PIN ` | | | -| | :ref:`BOARD_BUTTON_PIN `|* :ref:`isButtonPressed() ` | -|* :ref:`while ` | | | -| |* :ref:`Constants |* :ref:`waitForButtonPress() | -|* :ref:`do...while ` | ` (:ref:`integers | ` | -| | `, :ref:`floating | | -|* :ref:`break ` | point `) |**Analog I/O** | +|* :ref:`switch/case ` |* :ref:`Constants | | +| | ` (:ref:`integers |* :ref:`isButtonPressed() ` | +|* :ref:`while ` | `, :ref:`floating | | +| | point `) |* :ref:`waitForButtonPress() | +|* :ref:`do...while ` | | ` | +| |* :ref:`Board-specific values | | +|* :ref:`break ` | ` |**Analog I/O** | | | | | |* :ref:`continue ` |**Data Types** |* :ref:`analogRead() ` | | | | | @@ -76,7 +94,7 @@ A more exhaustive index is available at the :ref:`language-index`. |**Arithmetic Operators** | ` | | | | |* :ref:`delayMicroseconds() | |* :ref:`= ` |* ``unsigned long`` (4 bytes), synonym for | ` | -| (assignment operator) | :ref:`unsigned int ` | | +| (assignment) | :ref:`unsigned int ` | | | | | | |* :ref:`+ ` (addition) |* :ref:`long long ` (8 bytes) |**Math** | | | | | @@ -153,13 +171,13 @@ A more exhaustive index is available at the :ref:`language-index`. | | | | |* :ref:`++ ` | |* :ref:`Serial ` | | (increment) | | | -| | |**Looking for something else?** | +| | | | |* :ref:`- - ` | | | -| (decrement) | | See the :ref:`libraries` page for interfacing with| -| | | particular types of hardware. Maple links | -|* :ref:`+= ` | | against `newlib `_ | -| (compound add) | | and allows the use of any of its functions; see | -| | | its documentation for more details. | +| (decrement) | | | +| | | | +|* :ref:`+= ` | | | +| (compound add) | | | +| | | | |* :ref:`-= | | | | ` (compound | | | | subtract) | | | diff --git a/docs/source/libmaple.rst b/docs/source/libmaple.rst index 8cc39a3..9faca03 100644 --- a/docs/source/libmaple.rst +++ b/docs/source/libmaple.rst @@ -30,12 +30,12 @@ wrappers and code to imitate the Arduino programming library. git clone git://github.com/leaflabs/libmaple.git -**Table of contents:** +.. TODO after finishing refactor: create, style, and host a pure +.. Doxygen libmaple reference docs. This implies determining a stable +.. API. -.. toctree:: - :maxdepth: 2 +.. **Table of contents:** - Guide to using GCC's ARM target +.. .. toctree:: +.. :maxdepth: 2 -.. TODO LATER create, style, and host a pure Doxygen libmaple -.. reference docs. This implies determining a stable API. diff --git a/examples/qa-slave-shield.cpp b/examples/qa-slave-shield.cpp index 178b780..2da1c04 100644 --- a/examples/qa-slave-shield.cpp +++ b/examples/qa-slave-shield.cpp @@ -1,22 +1,20 @@ -// Slave mode for QA shield +// Slave mode for Quality Assurance test #include "wirish.h" -// FIXME generalize for Maple Native, Maple Mini (NUM_GPIO, Mini USB -// breakout pins, etc.) +#define INTER_TOGGLE_DELAY_NORMAL 5 +#define INTER_TOGGLE_DELAY_SLOW 80 -#define LED_PIN BOARD_LED_PIN -#define NUM_GPIO 38 // Ignore JTAG pins. +void interToggleDelay(void); void setup() { - /* Set up the LED to blink */ - pinMode(LED_PIN, OUTPUT); - digitalWrite(LED_PIN, HIGH); + pinMode(BOARD_LED_PIN, OUTPUT); + pinMode(BOARD_BUTTON_PIN, INPUT); - for(int i = 0; i < NUM_GPIO; i++) { - if (i == BOARD_LED_PIN) { + // All unused pins start out low. + for (int i = 0; i < BOARD_NR_GPIO_PINS; i++) { + if (boardUsesPin(i)) continue; - } pinMode(i, OUTPUT); digitalWrite(i, LOW); } @@ -28,17 +26,29 @@ void loop() { delay(100); toggleLED(); - for(int i = 0; i < NUM_GPIO; i++) { - if (i == BOARD_LED_PIN) { + for (int i = 0; i < BOARD_NR_GPIO_PINS; i++) { + if (boardUsesPin(i)) continue; - } - togglePin(i); - delay(5); - togglePin(i); - delay(5); + + // Bring just this pin high. + digitalWrite(i, HIGH); + // Give the master time to detect if any other pins also went high. + interToggleDelay(); + // Bring this pin back low again; all pins should now be low. + digitalWrite(i, LOW); + // Give the master time to detect if any pins are still high. + interToggleDelay(); } } +void interToggleDelay(void) { + if (digitalRead(BOARD_BUTTON_PIN)) { // don't pay the debouncing time + delay(INTER_TOGGLE_DELAY_SLOW); + } else { + delay(INTER_TOGGLE_DELAY_NORMAL); + } + } + // Force init to be called *first*, i.e. before static object allocation. // Otherwise, statically allocated objects that need libmaple may fail. __attribute__((constructor)) void premain() { @@ -48,7 +58,7 @@ __attribute__((constructor)) void premain() { int main(void) { setup(); - while (1) { + while (true) { loop(); } return 0; diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 110b219..a4128ac 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -1,49 +1,23 @@ // Interactive Test Session for LeafLabs Maple // Copyright (c) 2010 LeafLabs LLC. // -// Useful for testing Maple features and troubleshooting. Select a COMM port -// (SerialUSB or Serial2) before compiling and then enter 'h' at the prompt -// for a list of commands. +// Useful for testing Maple features and troubleshooting. +// Communicates over SerialUSB. #include "wirish.h" -#define LED_PIN BOARD_LED_PIN -#define PWM_PIN 3 - -// choose your weapon -#define COMM SerialUSB -//#define COMM Serial2 -//#define COMM Serial3 - +// ASCII escape character #define ESC ((uint8)27) -int rate = 0; - -#if defined(BOARD_maple) || defined(BOARD_maple_RET6) -const uint8 pwm_pins[] = - {0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 25, 27, 28}; -const uint8 adc_pins[] = - {0, 1, 2, 10, 11, 12, 13, 15, 16, 17, 18, 19, 20, 27, 28}; - -#elif defined(BOARD_maple_mini) -const uint8 pwm_pins[] = {3, 4, 5, 8, 9, 10, 11, 15, 16, 25, 26, 27}; -const uint8 adc_pins[] = {3, 4, 5, 6, 7, 8, 9, 10, 11, 33}; +// Default USART baud rate +#define BAUD 9600 -#elif defined(BOARD_maple_native) -const uint8 pwm_pins[] = {12, 13, 14, 15, 22, 23, 24, 25, 37, 38, 45, - 46, 47, 48, 49, 50, 53, 54}; -const uint8 adc_pins[] = {6, 7, 8, 9, 10, 11, 39, 40, 41, 42, 43, 45, - 46, 47, 48, 49, 50, 51, 52, 53, 54}; -#else -#error "Board type has not been selected correctly" +uint8 gpio_state[BOARD_NR_GPIO_PINS]; -#endif - -uint8 gpio_state[NR_GPIO_PINS]; - -const char* const dummy_dat = ("qwertyuiopasdfghjklzxcvbnmmmmmm,./1234567890-=" - "qwertyuiopasdfghjklzxcvbnm,./1234567890"); +const char* dummy_data = ("qwertyuiopasdfghjklzxcvbnmmmmmm,./1234567890-=" + "qwertyuiopasdfghjklzxcvbnm,./1234567890"); +// Commands void cmd_print_help(void); void cmd_adc_stats(void); void cmd_stressful_adc_stats(void); @@ -55,37 +29,43 @@ void cmd_gpio_qa(void); void cmd_sequential_gpio_writes(void); void cmd_gpio_toggling(void); void cmd_sequential_pwm_test(void); -void cmd_pwm_sweep(void); void cmd_servo_sweep(void); +void cmd_board_info(void); +// Helper functions void measure_adc_noise(uint8 pin); void fast_gpio(int pin); -void do_serials(HardwareSerial **serials, int n, unsigned baud); +void usart_baud_test(HardwareSerial **serials, int n, unsigned baud); void init_all_timers(uint16 prescale); +void enable_usarts(void); +void disable_usarts(void); +void print_board_array(const char* msg, const uint8 arr[], int len); + +// -- setup() and loop() ------------------------------------------------------ void setup() { // Set up the LED to blink pinMode(BOARD_LED_PIN, OUTPUT); // Start up the serial ports - Serial1.begin(9600); - Serial2.begin(9600); - Serial3.begin(9600); - - // Send a message out over COMM interface - COMM.println(" "); - COMM.println(" __ __ _ _"); - COMM.println(" | \\/ | __ _ _ __ | | ___| |"); - COMM.println(" | |\\/| |/ _` | '_ \\| |/ _ \\ |"); - COMM.println(" | | | | (_| | |_) | | __/_|"); - COMM.println(" |_| |_|\\__,_| .__/|_|\\___(_)"); - COMM.println(" |_|"); - COMM.println(" by leaflabs"); - COMM.println(""); - COMM.println(""); - COMM.println("Maple interactive test program (type '?' for help)"); - COMM.println("----------------------------------------------------------"); - COMM.print("> "); + Serial1.begin(BAUD); + Serial2.begin(BAUD); + Serial3.begin(BAUD); + + // Send a message out over SerialUSB interface + SerialUSB.println(" "); + SerialUSB.println(" __ __ _ _"); + SerialUSB.println(" | \\/ | __ _ _ __ | | ___| |"); + SerialUSB.println(" | |\\/| |/ _` | '_ \\| |/ _ \\ |"); + SerialUSB.println(" | | | | (_| | |_) | | __/_|"); + SerialUSB.println(" |_| |_|\\__,_| .__/|_|\\___(_)"); + SerialUSB.println(" |_|"); + SerialUSB.println(" by leaflabs"); + SerialUSB.println(""); + SerialUSB.println(""); + SerialUSB.println("Maple interactive test program (type '?' for help)"); + SerialUSB.println("----------------------------------------------------------"); + SerialUSB.print("> "); } @@ -93,16 +73,16 @@ void loop () { toggleLED(); delay(100); - while(COMM.available()) { - uint8 input = COMM.read(); - COMM.println(input); + while (SerialUSB.available()) { + uint8 input = SerialUSB.read(); + SerialUSB.println(input); switch(input) { case '\r': break; case ' ': - COMM.println("spacebar, nice!"); + SerialUSB.println("spacebar, nice!"); break; case '?': @@ -125,7 +105,7 @@ void loop () { break; case '.': - while(!COMM.available()) { + while (!SerialUSB.available()) { Serial1.print("."); Serial2.print("."); Serial3.print("."); @@ -146,17 +126,17 @@ void loop () { break; case 'W': - while(!COMM.available()) { - Serial1.print(dummy_dat); - Serial2.print(dummy_dat); - Serial3.print(dummy_dat); + while (!SerialUSB.available()) { + Serial1.print(dummy_data); + Serial2.print(dummy_data); + Serial3.print(dummy_data); } break; case 'U': - COMM.println("Dumping data to USB. Press any key."); - while(!COMM.available()) { - SerialUSB.print(dummy_dat); + SerialUSB.println("Dumping data to USB. Press any key."); + while (!SerialUSB.available()) { + SerialUSB.print(dummy_data); } break; @@ -169,10 +149,10 @@ void loop () { break; case 'f': - COMM.println("Wiggling D4 as fast as possible in bursts. " + SerialUSB.println("Wiggling D4 as fast as possible in bursts. " "Press any key."); - pinMode(4,OUTPUT); - while(!COMM.available()) { + pinMode(4, OUTPUT); + while (!SerialUSB.available()) { fast_gpio(4); delay(1); } @@ -182,19 +162,19 @@ void loop () { cmd_sequential_pwm_test(); break; - case 'P': - cmd_pwm_sweep(); - break; - case '_': - COMM.println("Delaying for 5 seconds..."); + SerialUSB.println("Delaying for 5 seconds..."); delay(5000); break; + // Be sure to update cmd_print_help() if you implement these: + case 't': // TODO + SerialUSB.println("Unimplemented."); break; case 'T': // TODO + SerialUSB.println("Unimplemented."); break; case 's': @@ -202,26 +182,30 @@ void loop () { break; case 'd': - COMM.println("Pulling down D4, D22. Press any key."); - pinMode(22,INPUT_PULLDOWN); - pinMode(4,INPUT_PULLDOWN); - while(!COMM.available()) { + SerialUSB.println("Pulling down D4, D22. Press any key."); + pinMode(22, INPUT_PULLDOWN); + pinMode(4, INPUT_PULLDOWN); + while (!SerialUSB.available()) { continue; } - COMM.println("Pulling up D4, D22. Press any key."); - pinMode(22,INPUT_PULLUP); - pinMode(4,INPUT_PULLUP); - while(!COMM.available()) { + SerialUSB.println("Pulling up D4, D22. Press any key."); + pinMode(22, INPUT_PULLUP); + pinMode(4, INPUT_PULLUP); + while (!SerialUSB.available()) { continue; } - COMM.read(); - pinMode(4,OUTPUT); + SerialUSB.read(); + pinMode(4, OUTPUT); break; + // Be sure to update cmd_print_help() if you implement these: + case 'i': // TODO + SerialUSB.println("Unimplemented."); break; case 'I': // TODO + SerialUSB.println("Unimplemented."); break; case 'r': @@ -232,391 +216,496 @@ void loop () { cmd_sequential_adc_reads(); break; + case 'b': + cmd_board_info(); + break; + case '+': cmd_gpio_qa(); break; default: // ------------------------------- - COMM.print("Unexpected: "); - COMM.print(input); - COMM.println(", press h for help."); + SerialUSB.print("Unexpected: "); + SerialUSB.print(input); + SerialUSB.println(", press h for help."); } - COMM.print("> "); + SerialUSB.print("> "); } } -void cmd_print_help(void) { - COMM.println(""); - //COMM.println("Command Listing\t(# means any digit)"); - COMM.println("Command Listing"); - COMM.println("\t?: print this menu"); - COMM.println("\th: print this menu"); - COMM.println("\tw: print Hello World on all 3 USARTS"); - COMM.println("\tn: measure noise and do statistics"); - COMM.println("\tN: measure noise and do statistics with background stuff"); - COMM.println("\ta: show realtime ADC info"); - COMM.println("\t.: echo '.' until new input"); - COMM.println("\tu: print Hello World on USB"); - COMM.println("\t_: do as little as possible for a couple seconds (delay)"); - COMM.println("\tp: test all PWM channels sequentially"); - COMM.println("\tW: dump data as fast as possible on all 3 USARTS"); - COMM.println("\tU: dump data as fast as possible on USB"); - COMM.println("\tg: toggle all GPIOs sequentialy"); - COMM.println("\tG: toggle all GPIOs at the same time"); - COMM.println("\tf: toggle GPIO D4 as fast as possible in bursts"); - COMM.println("\tP: simultaneously test all PWM channels with different " - "speeds/sweeps"); - COMM.println("\tr: Monitor and print GPIO status changes"); - COMM.println("\ts: output a sweeping servo PWM on all PWM channels"); - COMM.println("\tm: output data on USART1 and USART3 with various rates"); - COMM.println("\t+: test shield mode (for QA, will disrupt Serial2!)"); - - COMM.println("Unimplemented:"); - COMM.println("\te: do everything all at once until new input"); - COMM.println("\tt: output a 1khz squarewave on all GPIOs"); - COMM.println("\tT: output a 1hz squarewave on all GPIOs"); - COMM.println("\ti: print out a bunch of info about system state"); - COMM.println("\tI: print out status of all headers"); -} - -void measure_adc_noise(uint8 pin) { // TODO - uint16 data[100]; - float mean = 0; - //float stddev = 0; - float delta = 0; - float M2 = 0; - pinMode(pin, INPUT_ANALOG); - - // variance algorithm from knuth; see wikipedia - // checked against python - for(int i = 0; i<100; i++) { - data[i] = analogRead(pin); - delta = data[i] - mean; - mean = mean + delta/(i+1); - M2 = M2 + delta*(data[i] - mean); - } +// -- Commands ---------------------------------------------------------------- - //sqrt is broken? - //stddev = sqrt(variance); - COMM.print("header: D"); COMM.print(pin,DEC); - COMM.print("\tn: "); COMM.print(100,DEC); - COMM.print("\tmean: "); COMM.print(mean); - COMM.print("\tvariance: "); COMM.println(M2/99.0); - pinMode(pin, OUTPUT); +void cmd_print_help(void) { + SerialUSB.println(""); + SerialUSB.println("Command Listing"); + SerialUSB.println("\t?: print this menu"); + SerialUSB.println("\th: print this menu"); + SerialUSB.println("\tw: print Hello World on all 3 USARTS"); + SerialUSB.println("\tn: measure noise and do statistics"); + SerialUSB.println("\tN: measure noise and do statistics with background stuff"); + SerialUSB.println("\ta: show realtime ADC info"); + SerialUSB.println("\t.: echo '.' until new input"); + SerialUSB.println("\tu: print Hello World on USB"); + SerialUSB.println("\t_: do as little as possible for a couple seconds (delay)"); + SerialUSB.println("\tp: test all PWM channels sequentially"); + SerialUSB.println("\tW: dump data as fast as possible on all 3 USARTS"); + SerialUSB.println("\tU: dump data as fast as possible on USB"); + SerialUSB.println("\tg: toggle GPIOs sequentially"); + SerialUSB.println("\tG: toggle GPIOs at the same time"); + SerialUSB.println("\tf: toggle pin 4 as fast as possible in bursts"); + SerialUSB.println("\tr: monitor and print GPIO status changes"); + SerialUSB.println("\ts: output a sweeping servo PWM on all PWM channels"); + SerialUSB.println("\tm: output data on USART1 and USART3 with various rates"); + SerialUSB.println("\tb: print information about the board."); + SerialUSB.println("\t+: test shield mode (for quality assurance testing)"); + + SerialUSB.println("Unimplemented:"); + SerialUSB.println("\te: do everything all at once until new input"); + SerialUSB.println("\tt: output a 1khz squarewave on all GPIOs"); + SerialUSB.println("\tT: output a 1hz squarewave on all GPIOs"); + SerialUSB.println("\ti: print out a bunch of info about system state"); + SerialUSB.println("\tI: print out status of all headers"); } void cmd_adc_stats(void) { - COMM.println("Taking ADC noise stats..."); + SerialUSB.println("Taking ADC noise stats."); digitalWrite(BOARD_LED_PIN, 0); - for(uint32 i = 0; ibegin(9600); - } - while (!COMM.available()) { - for (int i = 0; i < n; i++) { - serials[i]->println(dummy_dat); - if (serials[i]->available()) { - serials[i]->println(serials[i]->read()); - delay(1000); - } - } - } + SerialUSB.println("Resetting USART1 and USART3..."); + Serial1.begin(BAUD); + Serial3.begin(BAUD); } void cmd_gpio_monitoring(void) { - COMM.println("Monitoring GPIO read state changes. Press any key."); - digitalWrite(BOARD_LED_PIN, 0); - // make sure to skip the TX/RX headers - for(int i = 2; i= j) COMM.print("#"); - else COMM.print(" "); + SerialUSB.print("Sequentially reading most ADC ports."); + SerialUSB.println("Press any key for next port, or ESC to stop."); + + for (uint32 i = 0; i < BOARD_NR_ADC_PINS; i++) { + if (boardUsesPin(i)) + continue; + + SerialUSB.print("Reading pin "); + SerialUSB.print(boardADCPins[i], DEC); + SerialUSB.println("..."); + pinMode(boardADCPins[i], INPUT_ANALOG); + while (!SerialUSB.available()) { + int sample = analogRead(boardADCPins[i]); + SerialUSB.print(boardADCPins[i], DEC); + SerialUSB.print("\t"); + SerialUSB.print(sample, DEC); + SerialUSB.print("\t"); + SerialUSB.print("|"); + for (int j = 0; j < 4096; j += 100) { + if (sample >= j) { + SerialUSB.print("#"); + } else { + SerialUSB.print(" "); + } } - COMM.print("| "); - for(int j = 0; j<12; j++) { - if(sample & (1 << (11-j))) COMM.print("1"); - else COMM.print("0"); + SerialUSB.print("| "); + for (int j = 0; j < 12; j++) { + if (sample & (1 << (11 - j))) { + SerialUSB.print("1"); + } else { + SerialUSB.print("0"); + } } - COMM.println(""); + SerialUSB.println(""); + } + pinMode(boardADCPins[i], OUTPUT); + digitalWrite(boardADCPins[i], 0); + if (SerialUSB.read() == ESC) + break; + } +} + +bool test_single_pin_is_high(int high_pin, const char* err_msg) { + bool ok = true; + for (int i = 0; i < BOARD_NR_GPIO_PINS; i++) { + if (boardUsesPin(i)) continue; + + if (digitalRead(i) == HIGH && i != high_pin) { + SerialUSB.println(); + SerialUSB.print("\t*** FAILURE! pin "); + SerialUSB.print(i, DEC); + SerialUSB.print(' '); + SerialUSB.println(err_msg); + ok = false; } - pinMode(adc_pins[i], OUTPUT); - digitalWrite(adc_pins[i], 0); - if((uint8)COMM.read() == ESC) break; } + return ok; +} + +bool wait_for_low_transition(uint8 pin) { + uint32 start = millis(); + while (millis() - start < 2000) { + if (digitalRead(pin) == LOW) { + return true; + } + } + return false; } void cmd_gpio_qa(void) { - COMM.println("Doing QA testing for most GPIO pins..."); - digitalWrite(BOARD_LED_PIN, 0); - for(int i = 0; i 65500) rate = 0; - for(uint32 i = 2; i 5734) rate = 4096; - for(uint32 i = 2; i 5734) + rate = 4096; + for (uint32 i = 0; i < BOARD_NR_PWM_PINS; i++) { + if (boardUsesPin(i)) + continue; + pwmWrite(boardPWMPins[i], rate); } delay(20); } - for(uint32 i = 2; ibegin(baud); + } + while (!SerialUSB.available()) { + for (int i = 0; i < n; i++) { + serials[i]->println(dummy_data); + if (serials[i]->available()) { + serials[i]->println(serials[i]->read()); + delay(1000); + } + } + } } static uint16 init_all_timers_prescale = 0; @@ -630,14 +719,42 @@ void init_all_timers(uint16 prescale) { timer_foreach(set_prescale); } +void enable_usarts(void) { + // FIXME generalize after USART refactor + Serial1.begin(BAUD); + Serial2.begin(BAUD); + Serial3.begin(BAUD); +} + +void disable_usarts(void) { + // FIXME generalize after USART refactor + Serial1.end(); + Serial2.end(); + Serial3.end(); +} + +void print_board_array(const char* msg, const uint8 arr[], int len) { + SerialUSB.print("\t"); + SerialUSB.print(msg); + SerialUSB.print(" ("); + SerialUSB.print(len); + SerialUSB.print("): "); + for (int i = 0; i < len; i++) { + SerialUSB.print(arr[i], DEC); + if (i < len - 1) SerialUSB.print(", "); + } + SerialUSB.println(); +} + +// -- premain() and main() ---------------------------------------------------- + // Force init to be called *first*, i.e. before static object allocation. // Otherwise, statically allocated objects that need libmaple may fail. -__attribute__(( constructor )) void premain() { +__attribute__((constructor)) void premain() { init(); } -int main(void) -{ +int main(void) { setup(); while (1) { diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 17f47c6..1c2b1c7 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -30,7 +30,7 @@ * at 72MHz. APB1 is clocked at 36MHz. */ -#include "wirish.h" +#include "boards.h" #include "flash.h" #include "rcc.h" @@ -46,15 +46,6 @@ static void setupClocks(void); static void setupADC(void); static void setupTimers(void); -/** - * @brief Generic board initialization function. - * - * This function is called before main(). It ensures that the clocks - * and peripherals are configured properly for use with wirish, then - * calls boardInit(). - * - * @see boardInit() - */ void init(void) { setupFlash(); setupClocks(); @@ -68,6 +59,17 @@ void init(void) { boardInit(); } +/* You could farm this out to the files in boards/ if e.g. it takes + * too long to test on Maple Native (all those FSMC pins...). */ +bool boardUsesPin(uint8 pin) { + for (int i = 0; i < BOARD_NR_USED_PINS; i++) { + if (pin == boardUsedPins[i]) { + return true; + } + } + return false; +} + static void setupFlash(void) { flash_enable_prefetch(); flash_set_latency(FLASH_WAIT_STATE_2); diff --git a/wirish/boards.h b/wirish/boards.h index 3d023ae..cec844f 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -63,8 +63,39 @@ enum { * @brief Maps each Maple pin to a corresponding stm32_pin_info. * @see stm32_pin_info */ -extern stm32_pin_info PIN_MAP[]; +extern const stm32_pin_info PIN_MAP[]; +/** + * @brief Pins capable of PWM output. + * + * Its length is BOARD_NR_PWM_PINS. + */ +extern const uint8 boardPWMPins[]; + +/** + * @brief Array of pins capable of analog input. + * + * Its length is BOARD_NR_ADC_PINS. + */ +extern const uint8 boardADCPins[]; + +/** + * @brief Pins which are connected to external hardware. + * + * For example, on Maple boards, it always at least includes + * BOARD_LED_PIN. Its length is BOARD_NR_USED_PINS. + */ +extern const uint8 boardUsedPins[]; + +/** + * @brief Generic board initialization function. + * + * This function is called before main(). It ensures that the clocks + * and peripherals are configured properly for use with wirish, then + * calls boardInit(). + * + * @see boardInit() + */ void init(void); /** @@ -78,6 +109,16 @@ void init(void); */ extern void boardInit(void); +/** + * @brief Test if a pin is used for a special purpose on your board. + * @param pin Pin to test + * @return true if the given pin is in boardUsedPins, and false otherwise. + * @see boardUsedPins + */ +bool boardUsesPin(uint8 pin); + +/* Include the appropriate private header from boards/: */ + #ifdef BOARD_maple #include "boards/maple.h" #elif defined(BOARD_maple_native) diff --git a/wirish/boards/maple.cpp b/wirish/boards/maple.cpp index ba2261b..5122290 100644 --- a/wirish/boards/maple.cpp +++ b/wirish/boards/maple.cpp @@ -40,7 +40,7 @@ void boardInit(void) { } -stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* Top header */ @@ -91,4 +91,16 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { {GPIOC, NULL, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ }; +extern const uint8 boardPWMPins[] __FLASH__ = { + 0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 25, 27, 28 +}; + +extern const uint8 boardADCPins[] __FLASH__ = { + 0, 1, 2, 10, 11, 12, 13, 15, 16, 17, 18, 19, 20, 27, 28 +}; + +extern const uint8 boardUsedPins[] __FLASH__ = { + BOARD_LED_PIN, BOARD_BUTTON_PIN +}; + #endif diff --git a/wirish/boards/maple.h b/wirish/boards/maple.h index 519698b..1867de8 100644 --- a/wirish/boards/maple.h +++ b/wirish/boards/maple.h @@ -42,7 +42,7 @@ #define BOARD_LED_PIN 13 /* Number of USARTs/UARTs whose pins are broken out to headers */ -#define NR_USARTS 3 +#define BOARD_NR_USARTS 3 /* Default USART pin numbers (not considering AFIO remap) */ #define BOARD_USART1_TX_PIN 7 @@ -53,7 +53,17 @@ #define BOARD_USART3_RX_PIN 30 /* Total number of GPIO pins that are broken out to headers and - intended for general use. */ -#define NR_GPIO_PINS 39 + * intended for general use. */ +#define BOARD_NR_GPIO_PINS 39 + +/* Number of pins capable of PWM output */ +#define BOARD_NR_PWM_PINS 16 + +/* Number of pins capable of ADC conversion */ +#define BOARD_NR_ADC_PINS 15 + +/* Number of pins already connected to external hardware. For Maple, + * these are just BOARD_LED_PIN and BOARD_BUTTON_PIN. */ +#define BOARD_NR_USED_PINS 2 #endif diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6.cpp index 962affc..fd67459 100644 --- a/wirish/boards/maple_RET6.cpp +++ b/wirish/boards/maple_RET6.cpp @@ -37,7 +37,7 @@ void boardInit(void) { } -stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* Top header */ @@ -88,4 +88,16 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { {GPIOC, TIMER8, NULL, 9, 4, ADCx} /* D38/PC9 (BUT) */ }; +extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { + 0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 25, 27, 28 +}; + +extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { + 0, 1, 2, 10, 11, 12, 13, 15, 16, 17, 18, 19, 20, 27, 28 +}; + +extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { + BOARD_LED_PIN, BOARD_BUTTON_PIN +}; + #endif diff --git a/wirish/boards/maple_RET6.h b/wirish/boards/maple_RET6.h index 63510c0..d91a4de 100644 --- a/wirish/boards/maple_RET6.h +++ b/wirish/boards/maple_RET6.h @@ -47,8 +47,7 @@ #define BOARD_LED_PIN 13 /* Note: UART4 and UART5 have pins which aren't broken out :( */ -#define NR_USARTS 3 - +#define BOARD_NR_USARTS 3 #define BOARD_USART1_TX_PIN 7 #define BOARD_USART1_RX_PIN 8 #define BOARD_USART2_TX_PIN 1 @@ -56,6 +55,9 @@ #define BOARD_USART3_TX_PIN 29 #define BOARD_USART3_RX_PIN 30 -#define NR_GPIO_PINS 39 +#define BOARD_NR_GPIO_PINS 39 +#define BOARD_NR_PWM_PINS 16 +#define BOARD_NR_ADC_PINS 15 +#define BOARD_NR_USED_PINS 2 #endif diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp index 66a0997..cd2827d 100644 --- a/wirish/boards/maple_mini.cpp +++ b/wirish/boards/maple_mini.cpp @@ -41,7 +41,7 @@ void boardInit(void) { afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); } -stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* Top header */ @@ -84,4 +84,19 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D33/PB1 */ }; +extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { + 3, 4, 5, 8, 9, 10, 11, 15, 16, 25, 26, 27 +}; + +extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { + 3, 4, 5, 6, 7, 8, 9, 10, 11, 33 // NB 33 is LED +}; + +#define USB_DP 23 +#define USB_DM 24 + +extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { + BOARD_LED_PIN, BOARD_BUTTON_PIN, USB_DP, USB_DM +}; + #endif diff --git a/wirish/boards/maple_mini.h b/wirish/boards/maple_mini.h index bfb92a5..8b7ae64 100644 --- a/wirish/boards/maple_mini.h +++ b/wirish/boards/maple_mini.h @@ -46,8 +46,7 @@ #define BOARD_BUTTON_PIN 32 #define BOARD_LED_PIN 33 -#define NR_USARTS 3 - +#define BOARD_NR_USARTS 3 #define BOARD_USART1_TX_PIN 26 #define BOARD_USART1_RX_PIN 25 #define BOARD_USART2_TX_PIN 9 @@ -55,6 +54,9 @@ #define BOARD_USART3_TX_PIN 1 #define BOARD_USART3_RX_PIN 0 -#define NR_GPIO_PINS 34 +#define BOARD_NR_GPIO_PINS 34 +#define BOARD_NR_PWM_PINS 12 +#define BOARD_NR_ADC_PINS 10 +#define BOARD_NR_USED_PINS 4 #endif diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index 75c6a2d..2813e91 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -39,7 +39,7 @@ void boardInit(void) { initNativeSRAM(); } -stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { +extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* Top header */ @@ -152,4 +152,18 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { {GPIOD, NULL, NULL, 10, 0, ADCx} /* D99/PD10 */ }; +extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { + 12, 13, 14, 15, 22, 23, 24, 25, 37, 38, 45, 46, 47, 48, 49, 50, 53, 54 +}; + +extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { + 6, 7, 8, 9, 10, 11, 39, 40, 41, 42, 43, 45, 46, 47, 48, 49, 50, 51, 52, 53, + 54 +}; + +/* FIXME! see comment by BOARD_NR_USED_PINS in maple_native.h */ +extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { + BOARD_LED_PIN, BOARD_BUTTON_PIN +}; + #endif diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h index 21fc480..4e3ee82 100644 --- a/wirish/boards/maple_native.h +++ b/wirish/boards/maple_native.h @@ -43,11 +43,10 @@ #define CYCLES_PER_MICROSECOND 72 #define SYSTICK_RELOAD_VAL 71999 -#define BOARD_LED_PIN D21 -#define BOARD_BUTTON_PIN D18 - -#define NR_USARTS 5 +#define BOARD_LED_PIN 21 +#define BOARD_BUTTON_PIN 18 +#define BOARD_NR_USARTS 5 #define BOARD_USART1_TX_PIN 25 #define BOARD_USART1_RX_PIN 26 #define BOARD_USART2_TX_PIN 51 @@ -59,6 +58,12 @@ #define BOARD_UART5_TX_PIN 20 #define BOARD_UART5_RX_PIN 28 -#define NR_GPIO_PINS 100 +#define BOARD_NR_GPIO_PINS 100 +#define BOARD_NR_PWM_PINS 18 +#define BOARD_NR_ADC_PINS 21 +/* FIXME! this isn't true at all; almost all of the triple header pins + * are used by the FSMC by default. Fix this (and the corresponding + * boardUsedPins definition in maple_native.cpp) by QA time. */ +#define BOARD_NR_USED_PINS 2 #endif diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp index 97a5ec3..8398878 100644 --- a/wirish/comm/HardwareSerial.cpp +++ b/wirish/comm/HardwareSerial.cpp @@ -32,10 +32,12 @@ #include "HardwareSerial.h" #include "usart.h" +// FIXME: High density device ports, usages of BOARD_USARTx_yX_PIN +// instead of holding onto a gpio_dev, tx_pin, rx_pin, timer_dev, and +// channel_num -- that stuff is all in the PIN_MAP. HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9, 10, TIMER1, 2); HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3); HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10, 11, NULL, 0); -// TODO: High density device ports HardwareSerial::HardwareSerial(uint8 usart_num, uint32 max_baud, diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp index f9ccd39..557fffd 100644 --- a/wirish/ext_interrupts.cpp +++ b/wirish/ext_interrupts.cpp @@ -43,7 +43,7 @@ static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode); * @see ExtIntTriggerMode */ void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { - if (pin >= NR_GPIO_PINS || !handler) { + if (pin >= BOARD_NR_GPIO_PINS || !handler) { return; } @@ -60,7 +60,7 @@ void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { * @param pin Pin number to detach any interrupt from. */ void detachInterrupt(uint8 pin) { - if (pin >= NR_GPIO_PINS) { + if (pin >= BOARD_NR_GPIO_PINS) { return; } diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp index 4c803d2..bf69bfb 100644 --- a/wirish/pwm.cpp +++ b/wirish/pwm.cpp @@ -34,7 +34,7 @@ void pwmWrite(uint8 pin, uint16 duty_cycle) { timer_dev *dev = PIN_MAP[pin].timer_device; - if (pin >= NR_GPIO_PINS || dev == NULL || dev->type == TIMER_BASIC) { + if (pin >= BOARD_NR_GPIO_PINS || dev == NULL || dev->type == TIMER_BASIC) { return; } diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp index 115e91e..9b9f175 100644 --- a/wirish/wirish_digital.cpp +++ b/wirish/wirish_digital.cpp @@ -33,7 +33,7 @@ void pinMode(uint8 pin, WiringPinMode mode) { gpio_pin_mode outputMode; boolean pwm = false; - if (pin >= NR_GPIO_PINS) { + if (pin >= BOARD_NR_GPIO_PINS) { return; } @@ -83,7 +83,7 @@ void pinMode(uint8 pin, WiringPinMode mode) { uint32 digitalRead(uint8 pin) { - if (pin >= NR_GPIO_PINS) { + if (pin >= BOARD_NR_GPIO_PINS) { return 0; } @@ -92,7 +92,7 @@ uint32 digitalRead(uint8 pin) { } void digitalWrite(uint8 pin, uint8 val) { - if (pin >= NR_GPIO_PINS) { + if (pin >= BOARD_NR_GPIO_PINS) { return; } @@ -100,14 +100,14 @@ void digitalWrite(uint8 pin, uint8 val) { } void togglePin(uint8 pin) { - if (pin >= NR_GPIO_PINS) { + if (pin >= BOARD_NR_GPIO_PINS) { return; } gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit); } -#define BUTTON_DEBOUNCE_DELAY 10 +#define BUTTON_DEBOUNCE_DELAY 1 uint8 isButtonPressed() { if (digitalRead(BOARD_BUTTON_PIN)) { diff --git a/wirish/wirish_types.h b/wirish/wirish_types.h index 7d6e31a..475f470 100644 --- a/wirish/wirish_types.h +++ b/wirish/wirish_types.h @@ -30,6 +30,7 @@ * @brief Wirish library type definitions. */ +#include "libmaple_types.h" #include "gpio.h" #include "timer.h" #include "adc.h" @@ -56,4 +57,6 @@ typedef struct stm32_pin_info { uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ } stm32_pin_info; +#define __FLASH__ __attr_flash + #endif -- cgit v1.2.3 From 300fa7122a9b896f507f637415c0fcd8effe2b88 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 30 Mar 2011 08:06:42 -0400 Subject: Hacks to get things to compile in the IDE. --- support/scripts/copy-to-ide | 7 +++- wirish/boards.h | 11 +++-- wirish/io.h | 3 +- wirish/time.cpp | 43 -------------------- wirish/time.h | 99 --------------------------------------------- wirish/wirish.h | 2 +- wirish/wirish_time.cpp | 43 ++++++++++++++++++++ wirish/wirish_time.h | 99 +++++++++++++++++++++++++++++++++++++++++++++ 8 files changed, 158 insertions(+), 149 deletions(-) delete mode 100644 wirish/time.cpp delete mode 100644 wirish/time.h create mode 100644 wirish/wirish_time.cpp create mode 100644 wirish/wirish_time.h (limited to 'wirish') diff --git a/support/scripts/copy-to-ide b/support/scripts/copy-to-ide index 5254974..674615e 100755 --- a/support/scripts/copy-to-ide +++ b/support/scripts/copy-to-ide @@ -23,6 +23,8 @@ LMAPLE_SRC="LICENSE ./wirish/*.cpp ./wirish/comm/*.cpp ./wirish/comm/*.h + ./wirish/boards/*.h + ./wirish/boards/*.cpp ./support/ld/common_ram.inc ./support/ld/common_rom.inc ./support/ld/libcs3_stm32_high_density.a @@ -52,6 +54,10 @@ cp -R $LMAPLE_SRC $DEST_CORES echo Copying over libraries cp -R libraries/* $DEST_LIBS +# libmaple version +echo Creating libmaple-version.txt +git show-ref HEAD | cut -c 1-10 > $DEST/libmaple-version.txt + # docs echo Deleting old reference directory contents rm -rf $DEST_REF/* @@ -62,5 +68,4 @@ echo Rebuilding documentation echo Copying over documentation cp -R $LMAPLE_DOCS_BUILD/* $DEST_REF - echo Done. diff --git a/wirish/boards.h b/wirish/boards.h index cec844f..8df7028 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -119,19 +119,22 @@ bool boardUsesPin(uint8 pin); /* Include the appropriate private header from boards/: */ +/* FIXME put boards/ before these paths once you stick make into the + * IDE; current situation is a hack. */ + #ifdef BOARD_maple -#include "boards/maple.h" +#include "maple.h" #elif defined(BOARD_maple_native) -#include "boards/maple_native.h" +#include "maple_native.h" #elif defined(BOARD_maple_mini) -#include "boards/maple_mini.h" +#include "maple_mini.h" #elif defined(BOARD_maple_RET6) /* * **NOT** MAPLE REV6. This the **Maple RET6 EDITION**, which is a * Maple with an STM32F103RET6 (...RET6) instead of an STM32F103RBT6 * (...RBT6) on it. Maple Rev6 (as of March 2011) DOES NOT EXIST. */ -#include "boards/maple_RET6.h" +#include "maple_RET6.h" #else #error "Board type has not been selected correctly." #endif diff --git a/wirish/io.h b/wirish/io.h index 4e415b5..137377d 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -33,7 +33,8 @@ #include "gpio.h" #include "adc.h" -#include "time.h" + +#include "wirish_time.h" /** * Specifies a GPIO pin behavior. diff --git a/wirish/time.cpp b/wirish/time.cpp deleted file mode 100644 index b5663b0..0000000 --- a/wirish/time.cpp +++ /dev/null @@ -1,43 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @brief Delay implementation. - */ - -#include "libmaple.h" -#include "systick.h" -#include "time.h" -#include "delay.h" - -void delay(unsigned long ms) { - uint32 i; - for (i = 0; i < ms; i++) { - delayMicroseconds(1000); - } -} - -void delayMicroseconds(uint32 us) { - delay_us(us); -} diff --git a/wirish/time.h b/wirish/time.h deleted file mode 100644 index a0c0c82..0000000 --- a/wirish/time.h +++ /dev/null @@ -1,99 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - *****************************************************************************/ - -/** - * @file time.h - * @brief Timing and delay functions. - */ - -#ifndef _TIME_H -#define _TIME_H - -#include "libmaple.h" -#include "nvic.h" -#include "systick.h" -#include "boards.h" - -#define US_PER_MS 1000 - -/** - * Returns time (in milliseconds) since the beginning of program - * execution. On overflow, restarts at 0. - * @see micros() - */ -static inline uint32 millis(void) { - return systick_timer_millis; -} - -/** - * Returns time (in microseconds) since the beginning of program - * execution. On overflow, restarts at 0. - * @see millis() - */ -static inline uint32 micros(void) { - uint32 ms; - uint32 cycle_cnt; - uint32 res; - - nvic_globalirq_disable(); - - cycle_cnt = systick_get_count(); - ms = millis(); - - nvic_globalirq_enable(); - - /* SYSTICK_RELOAD_VAL is 1 less than the number of cycles it - actually takes to complete a SysTick reload */ - res = (ms * US_PER_MS) + - (SYSTICK_RELOAD_VAL + 1 - cycle_cnt)/CYCLES_PER_MICROSECOND; - - return res; -} - -/** - * Delay for at least the given number of milliseconds. - * - * Interrupts, etc. may cause the actual number of milliseconds to - * exceed ms. However, this function will return no less than ms - * milliseconds from the time it is called. - * - * @param ms the number of milliseconds to delay. - * @see delayMicroseconds() - */ -void delay(unsigned long ms); - -/** - * Delay for at least the given number of microseconds. - * - * Interrupts, etc. may cause the actual number of microseconds to - * exceed us. However, this function will return no less than us - * microseconds from the time it is called. - * - * @param us the number of microseconds to delay. - * @see delay() - */ -void delayMicroseconds(uint32 us); - -#endif - diff --git a/wirish/wirish.h b/wirish/wirish.h index 880157d..4cc142d 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -40,7 +40,7 @@ #include "pwm.h" #include "ext_interrupts.h" #include "wirish_math.h" -#include "time.h" +#include "wirish_time.h" #include "HardwareSPI.h" #include "HardwareSerial.h" #include "usb_serial.h" diff --git a/wirish/wirish_time.cpp b/wirish/wirish_time.cpp new file mode 100644 index 0000000..2771e95 --- /dev/null +++ b/wirish/wirish_time.cpp @@ -0,0 +1,43 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @brief Delay implementation. + */ + +#include "libmaple.h" +#include "systick.h" +#include "wirish_time.h" +#include "delay.h" + +void delay(unsigned long ms) { + uint32 i; + for (i = 0; i < ms; i++) { + delayMicroseconds(1000); + } +} + +void delayMicroseconds(uint32 us) { + delay_us(us); +} diff --git a/wirish/wirish_time.h b/wirish/wirish_time.h new file mode 100644 index 0000000..a0c0c82 --- /dev/null +++ b/wirish/wirish_time.h @@ -0,0 +1,99 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2010 Perry Hung. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + *****************************************************************************/ + +/** + * @file time.h + * @brief Timing and delay functions. + */ + +#ifndef _TIME_H +#define _TIME_H + +#include "libmaple.h" +#include "nvic.h" +#include "systick.h" +#include "boards.h" + +#define US_PER_MS 1000 + +/** + * Returns time (in milliseconds) since the beginning of program + * execution. On overflow, restarts at 0. + * @see micros() + */ +static inline uint32 millis(void) { + return systick_timer_millis; +} + +/** + * Returns time (in microseconds) since the beginning of program + * execution. On overflow, restarts at 0. + * @see millis() + */ +static inline uint32 micros(void) { + uint32 ms; + uint32 cycle_cnt; + uint32 res; + + nvic_globalirq_disable(); + + cycle_cnt = systick_get_count(); + ms = millis(); + + nvic_globalirq_enable(); + + /* SYSTICK_RELOAD_VAL is 1 less than the number of cycles it + actually takes to complete a SysTick reload */ + res = (ms * US_PER_MS) + + (SYSTICK_RELOAD_VAL + 1 - cycle_cnt)/CYCLES_PER_MICROSECOND; + + return res; +} + +/** + * Delay for at least the given number of milliseconds. + * + * Interrupts, etc. may cause the actual number of milliseconds to + * exceed ms. However, this function will return no less than ms + * milliseconds from the time it is called. + * + * @param ms the number of milliseconds to delay. + * @see delayMicroseconds() + */ +void delay(unsigned long ms); + +/** + * Delay for at least the given number of microseconds. + * + * Interrupts, etc. may cause the actual number of microseconds to + * exceed us. However, this function will return no less than us + * microseconds from the time it is called. + * + * @param us the number of microseconds to delay. + * @see delay() + */ +void delayMicroseconds(uint32 us); + +#endif + -- cgit v1.2.3 From 88e3ec703947a78a7f50b4ae38a8cabbd60dc8db Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 1 Apr 2011 00:52:58 -0400 Subject: Broke the build with previous commit; sorry. --- wirish/rules.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/rules.mk b/wirish/rules.mk index 7715068..02906c7 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -27,7 +27,7 @@ cppSRCS_$(d) := wirish_math.cpp \ cxxabi-compat.cpp \ wirish_shift.cpp \ wirish_analog.cpp \ - time.cpp \ + wirish_time.cpp \ pwm.cpp \ ext_interrupts.cpp \ wirish_digital.cpp \ -- cgit v1.2.3 From 6229da7a3ec40fb7d87c0c4edd38bc32da36ef13 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 1 Apr 2011 02:33:53 -0400 Subject: NVIC and SCB refactor --- Makefile | 49 +++++------ libmaple/nvic.c | 83 ++++++------------- libmaple/nvic.h | 239 +++++++++++++++++++++++++++++++++--------------------- libmaple/rules.mk | 2 +- libmaple/scb.h | 48 ++++++----- libmaple/util.c | 4 +- wirish/boards.cpp | 15 +++- 7 files changed, 232 insertions(+), 208 deletions(-) (limited to 'wirish') diff --git a/Makefile b/Makefile index d31c9ed..d0cead4 100644 --- a/Makefile +++ b/Makefile @@ -39,6 +39,20 @@ ifeq ($(BOARD), maple_RET6) DENSITY := STM32_HIGH_DENSITY endif +# Some target specific things +ifeq ($(MEMORY_TARGET), ram) + LDSCRIPT := $(BOARD)/ram.ld + VECT_BASE_ADDR := VECT_TAB_RAM +endif +ifeq ($(MEMORY_TARGET), flash) + LDSCRIPT := $(BOARD)/flash.ld + VECT_BASE_ADDR := VECT_TAB_FLASH +endif +ifeq ($(MEMORY_TARGET), jtag) + LDSCRIPT := $(BOARD)/jtag.ld + VECT_BASE_ADDR := VECT_TAB_BASE +endif + # Useful paths ifeq ($(LIB_MAPLE_HOME),) SRCROOT := . @@ -51,24 +65,17 @@ SUPPORT_PATH := $(SRCROOT)/support # Compilation flags. # FIXME remove the ERROR_LED config -GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m \ - -nostdlib \ - -ffunction-sections -fdata-sections -Wl,--gc-sections \ - -DBOARD_$(BOARD) -DMCU_$(MCU) \ - -DERROR_LED_PORT=$(ERROR_LED_PORT) \ - -DERROR_LED_PIN=$(ERROR_LED_PIN) \ - -D$(DENSITY) -GLOBAL_CXXFLAGS := -fno-rtti -fno-exceptions -Wall \ +GLOBAL_FLAGS := -D$(VECT_BASE_ADDR) \ -DBOARD_$(BOARD) -DMCU_$(MCU) \ -DERROR_LED_PORT=$(ERROR_LED_PORT) \ -DERROR_LED_PIN=$(ERROR_LED_PIN) \ - -D$(DENSITY) + -D$(DENSITY) +GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m \ + -nostdlib -ffunction-sections -fdata-sections \ + -Wl,--gc-sections $(GLOBAL_FLAGS) +GLOBAL_CXXFLAGS := -fno-rtti -fno-exceptions -Wall $(GLOBAL_FLAGS) GLOBAL_ASFLAGS := -mcpu=cortex-m3 -march=armv7-m -mthumb \ - -x assembler-with-cpp \ - -DBOARD_$(BOARD) -DMCU_$(MCU) \ - -DERROR_LED_PORT=$(ERROR_LED_PORT) \ - -DERROR_LED_PIN=$(ERROR_LED_PIN) \ - -D$(DENSITY) + -x assembler-with-cpp $(GLOBAL_FLAGS) LDDIR := $(SUPPORT_PATH)/ld LDFLAGS = -T$(LDDIR)/$(LDSCRIPT) -L$(LDDIR) \ @@ -79,20 +86,6 @@ LDFLAGS = -T$(LDDIR)/$(LDSCRIPT) -L$(LDDIR) \ include $(SUPPORT_PATH)/make/build-rules.mk include $(SUPPORT_PATH)/make/build-templates.mk -# Some target specific things -ifeq ($(MEMORY_TARGET), ram) - LDSCRIPT := $(BOARD)/ram.ld - VECT_BASE_ADDR := VECT_TAB_RAM -endif -ifeq ($(MEMORY_TARGET), flash) - LDSCRIPT := $(BOARD)/flash.ld - VECT_BASE_ADDR := VECT_TAB_FLASH -endif -ifeq ($(MEMORY_TARGET), jtag) - LDSCRIPT := $(BOARD)/jtag.ld - VECT_BASE_ADDR := VECT_TAB_BASE -endif - # Set all submodules here LIBMAPLE_MODULES := $(SRCROOT)/libmaple LIBMAPLE_MODULES += $(SRCROOT)/wirish diff --git a/libmaple/nvic.c b/libmaple/nvic.c index 28ca169..28db96a 100644 --- a/libmaple/nvic.c +++ b/libmaple/nvic.c @@ -26,89 +26,54 @@ * @brief Nested interrupt controller routines */ -#include "libmaple.h" -#include "scb.h" #include "nvic.h" -#include "systick.h" - -void nvic_set_vector_table(uint32 addr, uint32 offset) { - __write(SCB_VTOR, (uint32)addr | (offset & 0x1FFFFF80)); -} - -/** - * @brief turn on interrupt number n - * @param n interrupt number - */ -void nvic_irq_enable(uint32 n) { - uint32 *iser = &((uint32*)NVIC_ISER0)[(n/32)]; - __write(iser, BIT(n % 32)); -} - -/** - * @brief turn off interrupt number n - * @param n interrupt number - */ -void nvic_irq_disable(uint32 n) { - uint32 *icer = &((uint32*)NVIC_ICER0)[(n/32)]; - __write(icer, BIT(n % 32)); -} - -void nvic_irq_disable_all(void) { - /* Each ICER register contains 1 bit per interrupt. Writing a 1 - to that bit disables the corresponding interrupt. So each of - the following lines disables up to 32 interrupts at a time. - Since low, medium, and high-density devices all have less than - 64 interrupts, this suffices. */ - /* TODO: fix for connectivity line: __write(NVIC_ICER2,1), - requires connectivity line support in libmaple.h */ - __write(NVIC_ICER0, 0xFFFFFFFF); - __write(NVIC_ICER1, 0xFFFFFFFF); -} - +#include "scb.h" +#include "stm32.h" /** * @brief Set interrupt priority for an interrupt line - * Note: The STM32 only implements 4 bits of priority, ignoring - * the lower 4 bits. This means there are only 16 levels of priority. - * Bits[3:0] read as zero and ignore writes. + * + * Note: The STM32 only implements 4 bits of priority, ignoring the + * lower 4 bits. This means there are only 16 levels of priority. + * Bits[3:0] read as zero and ignore writes. + * * @param irqn device to set - * @param priority priority to set, 0 being highest priority and 15 being - * lowest. + * @param priority Priority to set, 0 being highest priority and 15 + * being lowest. */ -void nvic_irq_set_priority(int32 irqn, uint8 priority) { +void nvic_irq_set_priority(nvic_irq_num irqn, uint8 priority) { if (irqn < 0) { /* This interrupt is in the system handler block */ - SCB->SHP[((uint32)irqn & 0xF) - 4] = (priority & 0xF) << 4; + SCB_BASE->SHP[((uint32)irqn & 0xF) - 4] = (priority & 0xF) << 4; } else { - NVIC->IP[irqn] = (priority & 0xF) << 4; + NVIC_BASE->IP[irqn] = (priority & 0xF) << 4; } } /** - * @brief Initialize the NVIC according to VECT_TAB_FLASH, - * VECT_TAB_RAM, or VECT_TAB_BASE. + * @brief Initialize the NVIC + * @param vect_table_address Vector table base address. */ -void nvic_init(void) { +void nvic_init(uint32 vector_table_address, uint32 offset) { uint32 i; -#ifdef VECT_TAB_FLASH - nvic_set_vector_table(USER_ADDR_ROM, 0x0); -#elif defined VECT_TAB_RAM - nvic_set_vector_table(USER_ADDR_RAM, 0x0); -#elif defined VECT_TAB_BASE - nvic_set_vector_table(((uint32)0x08000000), 0x0); -#else -#error "You must set a base address for the vector table!" -#endif + nvic_set_vector_table(vector_table_address, offset); /* * Lower priority level for all peripheral interrupts to lowest * possible. */ for (i = 0; i < NR_INTERRUPTS; i++) { - nvic_irq_set_priority(i, 0xF); + nvic_irq_set_priority((nvic_irq_num)i, 0xF); } /* Lower systick interrupt priority to lowest level */ nvic_irq_set_priority(NVIC_SYSTICK, 0xF); } + +/** + * Reset the vector table address. + */ +void nvic_set_vector_table(uint32 addr, uint32 offset) { + SCB_BASE->VTOR = addr | (offset & 0x1FFFFF80); +} diff --git a/libmaple/nvic.h b/libmaple/nvic.h index cbcd49c..a889f4b 100644 --- a/libmaple/nvic.h +++ b/libmaple/nvic.h @@ -24,115 +24,170 @@ /** * @file nvic.h - * @brief Nested interrupt controller defines and prototypes + * @brief Nested vector interrupt controller support. */ #ifndef _NVIC_H_ #define _NVIC_H_ +#include "libmaple_types.h" + #ifdef __cplusplus extern "C"{ #endif -#define NVIC_INT_USBHP 19 -#define NVIC_INT_USBLP 20 - -/* NVIC Interrupt Enable registers */ -#define NVIC_ISER0 0xE000E100 -#define NVIC_ISER1 0xE000E104 -/* NVIC_ISER2 only on connectivity line */ +/** NVIC register map type. */ +typedef struct nvic_reg_map { + __io uint32 ISER[8]; /**< Interrupt Set Enable Registers */ + uint32 RESERVED0[24]; /**< Reserved */ + __io uint32 ICER[8]; /**< Interrupt Clear Enable Registers */ + uint32 RSERVED1[24]; /**< Reserved */ + __io uint32 ISPR[8]; /**< Interrupt Set Pending Registers */ + uint32 RESERVED2[24]; /**< Reserved */ + __io uint32 ICPR[8]; /**< Interrupt Clear Pending Registers */ + uint32 RESERVED3[24]; /**< Reserved */ + __io uint32 IABR[8]; /**< Interrupt Active bit Registers */ + uint32 RESERVED4[56]; /**< Reserved */ + __io uint8 IP[240]; /**< Interrupt Priority Registers */ + uint32 RESERVED5[644]; /**< Reserved */ + __io uint32 STIR; /**< Software Trigger Interrupt Registers */ +} nvic_reg_map; -/* NVIC Interrupt Clear registers */ -#define NVIC_ICER0 0xE000E180 -#define NVIC_ICER1 0xE000E184 -/* NVIC_ICER2 only on connectivity line */ +/** NVIC register map base pointer. */ +#define NVIC_BASE ((nvic_reg_map*)0xE000E100) -/* NVIC Priority */ -#define NVIC_PRI_BASE 0xE000E400 +/** + * Interrupt vector table interrupt numbers. Each enumerator is the + * position of the corresponding interrupt in the vector table. */ +typedef enum nvic_irq_num { + NVIC_NMI = -14, /**< Non-maskable interrupt */ + NVIC_HARDFAULT = -13, /**< Hard fault (all class of fault) */ + NVIC_MEM_MANAGE = -12, /**< Memory management */ + NVIC_BUS_FAULT = -11, /**< Bus fault: prefetch fault, memory + access fault. */ + NVIC_USAGE_FAULT = -10, /**< Usage fault: Undefined instruction or + illegal state. */ + NVIC_SVC = -5, /**< System service call via SWI insruction */ + NVIC_DEBUG_MON = -4, /**< Debug monitor */ + NVIC_PEND_SVC = -2, /**< Pendable request for system service */ + NVIC_SYSTICK = -1, /**< System tick timer */ + NVIC_WWDG = 0, /**< Window watchdog interrupt */ + NVIC_PVD = 1, /**< PVD through EXTI line detection */ + NVIC_TAMPER = 2, /**< Tamper */ + NVIC_RTC = 3, /**< Real-time clock */ + NVIC_FLASH = 4, /**< Flash */ + NVIC_RCC = 5, /**< Reset and clock control */ + NVIC_EXTI0 = 6, /**< EXTI line 0 */ + NVIC_EXTI1 = 7, /**< EXTI line 1 */ + NVIC_EXTI2 = 8, /**< EXTI line 2 */ + NVIC_EXTI3 = 9, /**< EXTI line 3 */ + NVIC_EXTI4 = 10, /**< EXTI line 4 */ + NVIC_DMA_CH1 = 11, /**< DMA1 channel 1 */ + NVIC_DMA_CH2 = 12, /**< DMA1 channel 2 */ + NVIC_DMA_CH3 = 13, /**< DMA1 channel 3 */ + NVIC_DMA_CH4 = 14, /**< DMA1 channel 4 */ + NVIC_DMA_CH5 = 15, /**< DMA1 channel 5 */ + NVIC_DMA_CH6 = 16, /**< DMA1 channel 6 */ + NVIC_DMA_CH7 = 17, /**< DMA1 channel 7 */ + NVIC_ADC1_2 = 18, /**< ADC1 and ADC2 */ + NVIC_USB_HP_CAN_TX = 19, /**< USB high priority or CAN TX */ + NVIC_USB_LP_CAN_RX0 = 20, /**< USB low priority or CAN RX0 */ + NVIC_CAN_RX1 = 21, /**< CAN RX1 */ + NVIC_CAN_SCE = 22, /**< CAN SCE */ + NVIC_EXTI9_5 = 23, /**< EXTI line [9:5] */ + NVIC_TIMER1_BRK = 24, /**< Timer 1 break */ + NVIC_TIMER1_UP = 25, /**< Timer 1 update */ + NVIC_TIMER1_TRG_COM = 26, /**< Timer 1 trigger and commutation */ + NVIC_TIMER1_CC = 27, /**< Timer 1 capture/compare */ + NVIC_TIMER2 = 28, /**< Timer 2 */ + NVIC_TIMER3 = 29, /**< Timer 3 */ + NVIC_TIMER4 = 30, /**< Timer 4 */ + NVIC_I2C1_EV = 31, /**< I2C1 event */ + NVIC_I2C1_ER = 32, /**< I2C1 error */ + NVIC_I2C2_EV = 33, /**< I2C2 event */ + NVIC_I2C2_ER = 34, /**< I2C2 error */ + NVIC_SPI1 = 35, /**< SPI1 */ + NVIC_SPI2 = 36, /**< SPI2 */ + NVIC_USART1 = 37, /**< USART1 */ + NVIC_USART2 = 38, /**< USART2 */ + NVIC_USART3 = 39, /**< USART3 */ + NVIC_EXTI15_10 = 40, /**< EXTI line [15:10] */ + NVIC_RTCALARM = 41, /**< RTC alarm through EXTI line */ + NVIC_USBWAKEUP = 42, /**< USB wakeup from suspend through + EXTI line */ + NVIC_TIMER8_BRK = 43, /**< Timer 8 break */ + NVIC_TIMER8_UP = 44, /**< Timer 8 update */ + NVIC_TIMER8_TRG_COM = 45, /**< Timer 8 trigger and commutation */ + NVIC_TIMER8_CC = 46, /**< Timer 8 capture/compare */ +#ifdef STM32_HIGH_DENSITY + NVIC_ADC3 = 47, /**< ADC3 */ + NVIC_FSMC = 48, /**< FSMC */ + NVIC_SDIO = 49, /**< SDIO */ + NVIC_TIMER5 = 50, /**< Timer 5 */ + NVIC_SPI3 = 51, /**< SPI3 */ + NVIC_UART4 = 52, /**< UART4 */ + NVIC_UART5 = 53, /**< UART5 */ + NVIC_TIMER6 = 54, /**< Timer 6 */ + NVIC_TIMER7 = 55, /**< Timer 7 */ + NVIC_DMA2_CH1 = 56, /**< DMA2 channel 1 */ + NVIC_DMA2_CH2 = 57, /**< DMA2 channel 2 */ + NVIC_DMA2_CH3 = 58, /**< DMA2 channel 3 */ + NVIC_DMA2_CH4_5 = 59, /**< DMA2 channels 4 and 5 */ +#endif +} nvic_irq_num; -/* System control registers */ -#define SCB_VTOR 0xE000ED08 // Vector table offset register +void nvic_init(uint32 vector_table_address, uint32 offset); +void nvic_set_vector_table(uint32 address, uint32 offset); +void nvic_set_priority(nvic_irq_num irqn, uint8 priority); -#define NVIC_BASE 0xE000E100 -#define NVIC ((nvic_reg_map*)NVIC_BASE) +/** + * Enables interrupts and configurable fault handlers (clear PRIMASK). + */ +static inline void nvic_globalirq_enable() { + asm volatile("cpsie i"); +} -typedef struct nvic_reg_map { - __io uint32 ISER[8]; // Interrupt Set Enable Registers - uint32 RESERVED0[24]; - __io uint32 ICER[8]; // Interrupt Clear Enable Registers - uint32 RSERVED1[24]; - __io uint32 ISPR[8]; // Interrupt Set Pending Registers - uint32 RESERVED2[24]; - __io uint32 ICPR[8]; // Interrupt Clear Pending Registers - uint32 RESERVED3[24]; - __io uint32 IABR[8]; // Interrupt Active bit Registers - uint32 RESERVED4[56]; - __io uint8 IP[240]; // Interrupt Priority Registers - uint32 RESERVED5[644]; - __io uint32 STIR; // Software Trigger Interrupt Registers -} nvic_reg_map; +/** + * Disable interrupts and configurable fault handlers (set PRIMASK). + */ +static inline void nvic_globalirq_disable() { + asm volatile("cpsid i"); +} -typedef enum nvic_irq_num { - NVIC_NMI = -14, - NVIC_MEM_MANAGE = -12, - NVIC_BUS_FAULT = -11, - NVIC_USAGE_FAULT = -10, - NVIC_SVC = -5, - NVIC_DEBUG_MON = -4, - NVIC_PEND_SVC = -2, - NVIC_SYSTICK = -1, - - NVIC_TIMER1_BRK = 24, - NVIC_TIMER1_UP = 25, - NVIC_TIMER1_TRG_COM = 26, - NVIC_TIMER1_CC = 27, - NVIC_TIMER2 = 28, - NVIC_TIMER3 = 29, - NVIC_TIMER4 = 30, - NVIC_TIMER5 = 50, - NVIC_TIMER6 = 54, - NVIC_TIMER7 = 55, - NVIC_TIMER8_BRK = 43, - NVIC_TIMER8_UP = 44, - NVIC_TIMER8_TRG_COM = 45, - NVIC_TIMER8_CC = 46, - - NVIC_USART1 = 37, - NVIC_USART2 = 38, - NVIC_USART3 = 39, - NVIC_UART4 = 52, - NVIC_UART5 = 53, - - NVIC_EXTI0 = 6, - NVIC_EXTI1 = 7, - NVIC_EXTI2 = 8, - NVIC_EXTI3 = 9, - NVIC_EXTI4 = 10, - NVIC_EXTI9_5 = 23, - NVIC_EXTI15_10 = 40, - - NVIC_DMA_CH1 = 11, - NVIC_DMA_CH2 = 12, - NVIC_DMA_CH3 = 13, - NVIC_DMA_CH4 = 14, - NVIC_DMA_CH5 = 15, - NVIC_DMA_CH6 = 16, - NVIC_DMA_CH7 = 17, - - NVIC_I2C1_EV = 31, - NVIC_I2C1_ER = 32, - NVIC_I2C2_EV = 33, - NVIC_I2C2_ER = 34 -} nvic_irq_num; +/** + * @brief Enable interrupt irq_num + * @param irq_num Interrupt to enable + */ +static inline void nvic_irq_enable(nvic_irq_num irq_num) { + NVIC_BASE->ISER[irq_num / 32] = BIT(irq_num % 32); +} -#define nvic_globalirq_enable() asm volatile("cpsie i") -#define nvic_globalirq_disable() asm volatile("cpsid i") +/** + * @brief Disable interrupt irq_num + * @param irq_num Interrupt to disable + */ +static inline void nvic_irq_disable(nvic_irq_num irq_num) { + NVIC_BASE->ICER[irq_num / 32] = BIT(irq_num % 32); +} -void nvic_init(void); -void nvic_irq_enable(uint32 device); -void nvic_irq_disable(uint32 device); -void nvic_irq_disable_all(void); -void nvic_set_priority(int32 irqn, uint8 priority); +/** + * @brief Quickly disable all interrupts. + * + * Calling this function is significantly faster than calling + * nvic_irq_disable() in a loop. + */ +static inline void nvic_irq_disable_all(void) { + /* Note: This only works up to XL density. The fix for + * connectivity line is: + * + * NVIC_BASE->ICER[2] = 0xF; + * + * We don't support connectivity line devices (yet), so leave it + * alone for now. + */ + NVIC_BASE->ICER[0] = 0xFFFFFFFF; + NVIC_BASE->ICER[1] = 0xFFFFFFFF; +} #ifdef __cplusplus } diff --git a/libmaple/rules.mk b/libmaple/rules.mk index a9d7e50..2eaea55 100644 --- a/libmaple/rules.mk +++ b/libmaple/rules.mk @@ -9,7 +9,7 @@ BUILDDIRS += $(BUILD_PATH)/$(d)/usb/usb_lib LIBMAPLE_INCLUDES := -I$(LIBMAPLE_PATH) -I$(LIBMAPLE_PATH)/usb -I$(LIBMAPLE_PATH)/usb/usb_lib # Local flags -CFLAGS_$(d) = -I$(d) $(LIBMAPLE_INCLUDES) -D$(VECT_BASE_ADDR) +CFLAGS_$(d) = -I$(d) $(LIBMAPLE_INCLUDES) # Local rules and targets cSRCS_$(d) := adc.c \ diff --git a/libmaple/scb.h b/libmaple/scb.h index 8bfdda3..1911435 100644 --- a/libmaple/scb.h +++ b/libmaple/scb.h @@ -29,34 +29,32 @@ #ifndef _SCB_H_ #define _SCB_H_ -/* FIXME this definition is missing doxygen comments */ - +/** System control block register map */ typedef struct scb_reg_map { - __io uint32 CPUID; // CPU ID Base Register - __io uint32 ICSR; // Interrupt Control State Register - __io uint32 VTOR; // Vector Table Offset Register - __io uint32 AIRCR; // Application Interrupt / Reset Control Register - __io uint32 SCR; // System Control Register - __io uint32 CCR; // Configuration Control Register - __io uint8 SHP[12]; // System Handlers Priority Registers (4-7, 8-11, 12-15) - __io uint32 SHCSR; // System Handler Control and State Register - __io uint32 CFSR; // Configurable Fault Status Register - __io uint32 HFSR; // Hard Fault Status Register - __io uint32 DFSR; // Debug Fault Status Register - __io uint32 MMFAR; // Mem Manage Address Register - __io uint32 BFAR; // Bus Fault Address Register - __io uint32 AFSR; // Auxiliary Fault Status Register - __io uint32 PFR[2]; // Processor Feature Register - __io uint32 DFR; // Debug Feature Register - __io uint32 ADR; // Auxiliary Feature Register - __io uint32 MMFR[4]; // Memory Model Feature Register - __io uint32 ISAR[5]; // ISA Feature Register + __io uint32 CPUID; /**< CPU ID Base Register */ + __io uint32 ICSR; /**< Interrupt Control State Register */ + __io uint32 VTOR; /**< Vector Table Offset Register */ + __io uint32 AIRCR; /**< Application Interrupt / Reset Control Register */ + __io uint32 SCR; /**< System Control Register */ + __io uint32 CCR; /**< Configuration Control Register */ + __io uint8 SHP[12]; /**< System Handlers Priority Registers + (4-7, 8-11, 12-15) */ + __io uint32 SHCSR; /**< System Handler Control and State Register */ + __io uint32 CFSR; /**< Configurable Fault Status Register */ + __io uint32 HFSR; /**< Hard Fault Status Register */ + __io uint32 DFSR; /**< Debug Fault Status Register */ + __io uint32 MMFAR; /**< Mem Manage Address Register */ + __io uint32 BFAR; /**< Bus Fault Address Register */ + __io uint32 AFSR; /**< Auxiliary Fault Status Register */ + __io uint32 PFR[2]; /**< Processor Feature Register */ + __io uint32 DFR; /**< Debug Feature Register */ + __io uint32 ADR; /**< Auxiliary Feature Register */ + __io uint32 MMFR[4]; /**< Memory Model Feature Register */ + __io uint32 ISAR[5]; /**< ISA Feature Register */ } scb_reg_map; -/* FIXME these names violate the libmaple naming conventions */ - -#define SCB_BASE 0xE000ED00 -#define SCB ((scb_reg_map*)(SCB_BASE)) +/** System control block register map base pointer */ +#define SCB_BASE ((struct scb_reg_map*)0xE000ED00) #endif diff --git a/libmaple/util.c b/libmaple/util.c index 6b4f216..77af5b8 100644 --- a/libmaple/util.c +++ b/libmaple/util.c @@ -69,8 +69,8 @@ void __error(void) { usart_disable_all(); /* Turn the USB interrupt back on so the bootloader keeps on functioning */ - nvic_irq_enable(NVIC_INT_USBHP); - nvic_irq_enable(NVIC_INT_USBLP); + nvic_irq_enable(NVIC_USB_HP_CAN_TX); + nvic_irq_enable(NVIC_USB_LP_CAN_RX0); /* Reenable global interrupts */ nvic_globalirq_enable(); diff --git a/wirish/boards.cpp b/wirish/boards.cpp index 1c2b1c7..9e25eeb 100644 --- a/wirish/boards.cpp +++ b/wirish/boards.cpp @@ -43,13 +43,14 @@ static void setupFlash(void); static void setupClocks(void); +static void setupNVIC(void); static void setupADC(void); static void setupTimers(void); void init(void) { setupFlash(); setupClocks(); - nvic_init(); + setupNVIC(); systick_init(SYSTICK_RELOAD_VAL); gpio_init_all(); afio_init(); @@ -90,6 +91,18 @@ static void setupClocks() { rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); } +static void setupNVIC() { +#ifdef VECT_TAB_FLASH + nvic_init(USER_ADDR_ROM, 0); +#elif defined VECT_TAB_RAM + nvic_init(USER_ADDR_RAM, 0); +#elif defined VECT_TAB_BASE + nvic_init((uint32)0x08000000, 0); +#else +#error "You must select a base address for the vector table." +#endif +} + static void adcDefaultConfig(const adc_dev* dev); static void setupADC() { -- cgit v1.2.3 From 552b8882ef04cb0028ec30a04b5464b1a17bccad Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 6 Apr 2011 13:57:30 -0400 Subject: USART refactor. --- docs/source/lang/api/serial.rst | 5 +- examples/test-serial-flush.cpp | 29 ++-- examples/test-session.cpp | 62 ++++++-- libmaple/usart.c | 302 +++++++++++++++++++------------------- libmaple/usart.h | 315 ++++++++++++++++++++++++++++++++-------- libmaple/util.c | 53 ++++--- wirish/comm/HardwareSerial.cpp | 86 ++++++----- wirish/comm/HardwareSerial.h | 50 +++---- 8 files changed, 582 insertions(+), 320 deletions(-) (limited to 'wirish') diff --git a/docs/source/lang/api/serial.rst b/docs/source/lang/api/serial.rst index 58002e3..29c70a2 100644 --- a/docs/source/lang/api/serial.rst +++ b/docs/source/lang/api/serial.rst @@ -12,6 +12,9 @@ devices. Introduction ------------ +.. FIXME remove Maple-specific documentation +.. FIXME Serial4, Serial5 updates for high-density devices + The Maple has three serial ports (also known as a UARTs or USARTs): ``Serial1``, ``Serial2``, and ``Serial3``. They communicate using the pins summarized in the following table: @@ -221,7 +224,7 @@ Arduino Compatibility Note Unlike the Arduino, none of the Maple's serial ports is connected to the USB port on the Maple board (for that, use :ref:`SerialUSB `). Thus, to use these pins to communicate with your -personal computer, you will need an additional USB-to-serial adaptor. +personal computer, you will need an additional USB-to-serial adapter. .. TODO LATER port these examples over diff --git a/examples/test-serial-flush.cpp b/examples/test-serial-flush.cpp index 1cd82b6..6c4e100 100644 --- a/examples/test-serial-flush.cpp +++ b/examples/test-serial-flush.cpp @@ -1,21 +1,26 @@ -// Tests the "flush" Serial function +/* + * Tests the "flush" Serial function. + */ #include "wirish.h" +#define COMM Serial1 + void setup() { - /* Send a message out USART2 */ - Serial2.begin(9600); - Serial2.println("Hello world!"); + COMM.begin(9600); + COMM.println("Hello world!"); } void loop() { - Serial2.println("Waiting for multiple input..."); - while(Serial2.available() < 5) { } - Serial2.println(Serial2.read()); - Serial2.println(Serial2.read()); - Serial2.flush(); - if(Serial2.available()) { - Serial2.println("FAIL! Still had junk in the buffer..."); + COMM.println("Waiting for multiple input..."); + while (COMM.available() < 5) + ; + COMM.println(COMM.read()); + COMM.println(COMM.read()); + COMM.flush(); + + if (COMM.available()) { + COMM.println("FAIL! Still had junk in the buffer..."); } } @@ -28,7 +33,7 @@ __attribute__((constructor)) void premain() { int main(void) { setup(); - while (1) { + while (true) { loop(); } return 0; diff --git a/examples/test-session.cpp b/examples/test-session.cpp index a4128ac..01d0fe9 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -23,6 +23,7 @@ void cmd_adc_stats(void); void cmd_stressful_adc_stats(void); void cmd_everything(void); void cmd_serial1_serial3(void); +void cmd_serial1_echo(void); void cmd_gpio_monitoring(void); void cmd_sequential_adc_reads(void); void cmd_gpio_qa(void); @@ -35,7 +36,8 @@ void cmd_board_info(void); // Helper functions void measure_adc_noise(uint8 pin); void fast_gpio(int pin); -void usart_baud_test(HardwareSerial **serials, int n, unsigned baud); +void serial_baud_test(HardwareSerial **serials, int n, unsigned baud); +void serial_echo_test(HardwareSerial *serial, unsigned baud); void init_all_timers(uint16 prescale); void enable_usarts(void); void disable_usarts(void); @@ -104,6 +106,10 @@ void loop () { cmd_serial1_serial3(); break; + case 'E': + cmd_serial1_echo(); + break; + case '.': while (!SerialUSB.available()) { Serial1.print("."); @@ -225,8 +231,8 @@ void loop () { break; default: // ------------------------------- - SerialUSB.print("Unexpected: "); - SerialUSB.print(input); + SerialUSB.print("Unexpected byte: 0x"); + SerialUSB.print((int)input, HEX); SerialUSB.println(", press h for help."); } @@ -243,11 +249,13 @@ void cmd_print_help(void) { SerialUSB.println("\th: print this menu"); SerialUSB.println("\tw: print Hello World on all 3 USARTS"); SerialUSB.println("\tn: measure noise and do statistics"); - SerialUSB.println("\tN: measure noise and do statistics with background stuff"); + SerialUSB.println("\tN: measure noise and do statistics with background " + "stuff"); SerialUSB.println("\ta: show realtime ADC info"); SerialUSB.println("\t.: echo '.' until new input"); SerialUSB.println("\tu: print Hello World on USB"); - SerialUSB.println("\t_: do as little as possible for a couple seconds (delay)"); + SerialUSB.println("\t_: do as little as possible for a couple seconds " + "(delay)"); SerialUSB.println("\tp: test all PWM channels sequentially"); SerialUSB.println("\tW: dump data as fast as possible on all 3 USARTS"); SerialUSB.println("\tU: dump data as fast as possible on USB"); @@ -256,7 +264,9 @@ void cmd_print_help(void) { SerialUSB.println("\tf: toggle pin 4 as fast as possible in bursts"); SerialUSB.println("\tr: monitor and print GPIO status changes"); SerialUSB.println("\ts: output a sweeping servo PWM on all PWM channels"); - SerialUSB.println("\tm: output data on USART1 and USART3 with various rates"); + SerialUSB.println("\tm: output data on USART1 and USART3 at various " + "baud rates"); + SerialUSB.println("\tE: echo data on USART1 at various baud rates"); SerialUSB.println("\tb: print information about the board."); SerialUSB.println("\t+: test shield mode (for quality assurance testing)"); @@ -316,17 +326,17 @@ void cmd_serial1_serial3(void) { SerialUSB.println("Testing 57600 baud on USART1 and USART3. " "Press any key to stop."); - usart_baud_test(serial_1_and_3, 2, 57600); + serial_baud_test(serial_1_and_3, 2, 57600); SerialUSB.read(); SerialUSB.println("Testing 115200 baud on USART1 and USART3. " "Press any key to stop."); - usart_baud_test(serial_1_and_3, 2, 115200); + serial_baud_test(serial_1_and_3, 2, 115200); SerialUSB.read(); SerialUSB.println("Testing 9600 baud on USART1 and USART3. " "Press any key to stop."); - usart_baud_test(serial_1_and_3, 2, 9600); + serial_baud_test(serial_1_and_3, 2, 9600); SerialUSB.read(); SerialUSB.println("Resetting USART1 and USART3..."); @@ -334,6 +344,27 @@ void cmd_serial1_serial3(void) { Serial3.begin(BAUD); } +void cmd_serial1_echo(void) { + SerialUSB.println("Testing serial echo at various baud rates. " + "Press any key for next baud rate, or ESC to quit " + "early."); + while (!SerialUSB.available()) + ; + SerialUSB.read(); + + SerialUSB.println("Testing 115200 baud on USART1."); + serial_echo_test(&Serial1, 115200); + if (SerialUSB.read() == ESC) return; + + SerialUSB.println("Testing 57600 baud on USART1."); + serial_echo_test(&Serial1, 57600); + if (SerialUSB.read() == ESC) return; + + SerialUSB.println("Testing 9600 baud on USART1."); + serial_echo_test(&Serial1, 9600); + if (SerialUSB.read() == ESC) return; +} + void cmd_gpio_monitoring(void) { SerialUSB.println("Monitoring pin state changes. Press any key to stop."); @@ -615,7 +646,7 @@ void cmd_board_info(void) { // TODO print more information SerialUSB.println("Board information"); SerialUSB.println("================="); - SerialUSB.print("* Clock speed (cycles/us): "); + SerialUSB.print("* Clock speed (MHz): "); SerialUSB.println(CYCLES_PER_MICROSECOND); SerialUSB.print("* BOARD_LED_PIN: "); @@ -693,7 +724,7 @@ void fast_gpio(int maple_pin) { gpio_toggle_bit(dev, bit); } -void usart_baud_test(HardwareSerial **serials, int n, unsigned baud) { +void serial_baud_test(HardwareSerial **serials, int n, unsigned baud) { for (int i = 0; i < n; i++) { serials[i]->begin(baud); } @@ -708,6 +739,15 @@ void usart_baud_test(HardwareSerial **serials, int n, unsigned baud) { } } +void serial_echo_test(HardwareSerial *serial, unsigned baud) { + serial->begin(baud); + while (!SerialUSB.available()) { + if (!serial->available()) + continue; + serial->print(serial->read()); + } +} + static uint16 init_all_timers_prescale = 0; static void set_prescale(timer_dev *dev) { diff --git a/libmaple/usart.c b/libmaple/usart.c index 494a29f..df5e2c5 100644 --- a/libmaple/usart.c +++ b/libmaple/usart.c @@ -23,212 +23,214 @@ *****************************************************************************/ /** + * @file usart.c * @brief USART control routines */ -#include "libmaple.h" -#include "rcc.h" -#include "nvic.h" #include "usart.h" -#define USART1_BASE 0x40013800 -#define USART2_BASE 0x40004400 -#define USART3_BASE 0x40004800 -#define UART4_BASE 0x40004C00 // High-density devices only (Maple Native) -#define UART5_BASE 0x40005000 // High-density devices only (Maple Native) - -#define USART_UE BIT(13) -#define USART_M BIT(12) -#define USART_TE BIT(3) -#define USART_RE BIT(2) -#define USART_RXNEIE BIT(5) // read data register not empty interrupt enable -#define USART_TC BIT(6) - -/* usart descriptor table */ -struct usart_dev usart_dev_table[] = { - [USART1] = { - .base = (usart_port*)USART1_BASE, - .rcc_dev_num = RCC_USART1, - .nvic_dev_num = NVIC_USART1 - }, - [USART2] = { - .base = (usart_port*)USART2_BASE, - .rcc_dev_num = RCC_USART2, - .nvic_dev_num = NVIC_USART2 - }, - [USART3] = { - .base = (usart_port*)USART3_BASE, - .rcc_dev_num = RCC_USART3, - .nvic_dev_num = NVIC_USART3 - }, -#ifdef STM32_HIGH_DENSITY - /* TODO test */ - [UART4] = { - .base = (usart_port*)UART4_BASE, - .rcc_dev_num = RCC_UART4, - .nvic_dev_num = NVIC_UART4 - }, - [UART5] = { - .base = (usart_port*)UART5_BASE, - .rcc_dev_num = RCC_UART5, - .nvic_dev_num = NVIC_UART5 - }, -#endif -}; - /* - * Usart interrupt handlers. + * Devices */ -static inline void usart_irq(int usart_num) { -#ifdef USART_SAFE_INSERT - /* Ignore old bytes if the user defines USART_SAFE_INSERT. */ - rb_safe_insert(&(usart_dev_table[usart_num].rb), - (uint8)((usart_dev_table[usart_num].base)->DR)); -#else - /* By default, push bytes around in the ring buffer. */ - rb_push_insert(&(usart_dev_table[usart_num].rb), - (uint8)((usart_dev_table[usart_num].base)->DR)); -#endif -} - -/* TODO: Check the disassembly for the following functions to make - sure GCC inlined properly. */ - -void __irq_usart1(void) { - usart_irq(USART1); -} - -void __irq_usart2(void) { - usart_irq(USART2); -} - -void __irq_usart3(void) { - usart_irq(USART3); -} +static ring_buffer usart1_rb; +static usart_dev usart1 = { + .regs = USART1_BASE, + .rb = &usart1_rb, + .max_baud = 4500000UL, + .clk_id = RCC_USART1, + .irq_num = NVIC_USART1 +}; +usart_dev *USART1 = &usart1; + +static ring_buffer usart2_rb; +static usart_dev usart2 = { + .regs = USART2_BASE, + .rb = &usart2_rb, + .max_baud = 2250000UL, + .clk_id = RCC_USART2, + .irq_num = NVIC_USART2 +}; +usart_dev *USART2 = &usart2; + +static ring_buffer usart3_rb; +static usart_dev usart3 = { + .regs = USART3_BASE, + .rb = &usart3_rb, + .max_baud = 2250000UL, + .clk_id = RCC_USART3, + .irq_num = NVIC_USART3 +}; +usart_dev *USART3 = &usart3; #ifdef STM32_HIGH_DENSITY -void __irq_uart4(void) { - usart_irq(UART4); -} - -void __irq_uart5(void) { - usart_irq(UART5); -} +static ring_buffer uart4_rb; +static usart_dev uart4 = { + .regs = UART4_BASE, + .rb = &uart4_rb, + .max_baud = 2250000UL, + .clk_id = RCC_UART4, + .irq_num = NVIC_UART4 +}; +usart_dev *UART4 = &uart4; + +static ring_buffer uart5_rb; +static usart_dev uart5 = { + .regs = UART5_BASE, + .rb = &uart5_rb, + .max_baud = 2250000UL, + .clk_id = RCC_UART5, + .irq_num = NVIC_UART5 +}; +usart_dev *UART5 = &uart5; #endif /** - * @brief Enable a USART in single buffer transmission mode, multibuffer - * receiver mode. - * @param usart_num USART to be initialized - * @param baud Baud rate to be set at + * @brief Initialize a serial port. + * @param dev Serial port to be initialized */ -void usart_init(uint8 usart_num, uint32 baud) { -#ifdef STM32_HIGH_DENSITY - ASSERT(usart_num <= UART5); -#else - ASSERT(usart_num <= USART3); -#endif - usart_port *port; - ring_buffer *ring_buf; +void usart_init(usart_dev *dev) { + rb_init(dev->rb, USART_RX_BUF_SIZE, dev->rx_buf); + rcc_clk_enable(dev->clk_id); + nvic_irq_enable(dev->irq_num); +} - uint32 clk_speed; +/** + * @brief Configure a serial port's baud rate. + * + * @param dev Serial port to be configured + * @param clock_speed MCU clock speed, in megahertz. + * @param baud Baud rate for transmit/receive. + */ +void usart_set_baud_rate(usart_dev *dev, uint32 clock_speed, uint32 baud) { uint32 integer_part; uint32 fractional_part; uint32 tmp; - port = usart_dev_table[usart_num].base; - rcc_clk_enable(usart_dev_table[usart_num].rcc_dev_num); - nvic_irq_enable(usart_dev_table[usart_num].nvic_dev_num); - - /* usart1 is mad fast */ - clk_speed = (usart_num == USART1) ? 72000000UL : 36000000UL; - - /* Initialize rx ring buffer */ - rb_init(&usart_dev_table[usart_num].rb, - sizeof (usart_dev_table[usart_num].rx_buf), - usart_dev_table[usart_num].rx_buf); - - /* Set baud rate */ - integer_part = ((25 * clk_speed) / (4 * baud)); + /* See ST RM0008 for the details on configuring the baud rate register */ + integer_part = (25 * clock_speed) / (4 * baud); tmp = (integer_part / 100) << 4; - fractional_part = integer_part - (100 * (tmp >> 4)); tmp |= (((fractional_part * 16) + 50) / 100) & ((uint8)0x0F); - port->BRR = (uint16)tmp; - - port->CR1 = USART_TE | // transmitter enable - USART_RE | // receiver enable - USART_RXNEIE; // receive interrupt enable - - - /* Enable the USART and set mode to 8n1 */ - port->CR1 |= USART_UE; + dev->regs->BRR = (uint16)tmp; } /** - * @brief Turn off all USARTs. + * @brief Enable a serial port. + * + * USART is enabled in single buffer transmission mode, multibuffer + * receiver mode, at the given baud rate, 8n1. + * + * Serial port must have a baud rate configured to work properly. + * + * @param dev Serial port to enable. + * @see usart_set_baud_rate() */ -void usart_disable_all() { - usart_disable(USART1); - usart_disable(USART2); - usart_disable(USART3); -#ifdef STM32_HIGH_DENSITY - usart_disable(UART4); - usart_disable(UART5); -#endif +void usart_enable(usart_dev *dev) { + usart_reg_map *regs = dev->regs; + regs->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_RXNEIE; + regs->CR1 |= USART_CR1_UE; } /** - * @brief Turn off a USART. - * @param USART to be disabled + * @brief Turn off a serial port. + * @param dev Serial port to be disabled */ -void usart_disable(uint8 usart_num) { - usart_port *port = usart_dev_table[usart_num].base; +void usart_disable(usart_dev *dev) { + /* FIXME this misbehaves if you try to use PWM on TX afterwards */ + usart_reg_map *regs = dev->regs; - /* TC bit must be high before disabling the usart */ - while((port->CR1 & USART_UE) && !(port->SR & USART_TC)) + /* TC bit must be high before disabling the USART */ + while((regs->CR1 & USART_CR1_UE) && !(regs->SR & USART_SR_TC)) ; /* Disable UE */ - port->CR1 = 0; + regs->CR1 = 0; /* Clean up buffer */ - usart_reset_rx(usart_num); + usart_reset_rx(dev); } +/** + * @brief Call a function on each USART. + * @param fn Function to call. + */ +void usart_foreach(void (*fn)(usart_dev *dev)) { + fn(USART1); + fn(USART2); + fn(USART3); +#ifdef STM32_HIGH_DENSITY + fn(UART4); + fn(UART5); +#endif +} /** - * @brief Print a null terminated string to the specified USART - * - * @param usart_num usart to send on - * @param str string to send + * @brief Print a null-terminated string to the specified serial port. + * @param dev Serial port to send the string on + * @param str String to send */ -void usart_putstr(uint8 usart_num, const char* str) { +void usart_putstr(usart_dev *dev, const char* str) { char ch; - while((ch = *(str++)) != '\0') { - usart_putc(usart_num, ch); + while ((ch = *(str++)) != '\0') { + usart_putc(dev, ch); } } /** - * @brief Print an unsigned integer to the specified usart + * @brief Print an unsigned integer to the specified serial port. * - * @param usart_num usart to send on - * @param val number to print + * @param dev Serial port to send on + * @param val Number to print */ -void usart_putudec(uint8 usart_num, uint32 val) { +void usart_putudec(usart_dev *dev, uint32 val) { char digits[12]; - int i; + int i = 0; - i = 0; do { digits[i++] = val % 10 + '0'; val /= 10; } while (val > 0); + while (--i >= 0) { - usart_putc(usart_num, digits[i]); + usart_putc(dev, digits[i]); } } + +/* + * Interrupt handlers. + */ + +static inline void usart_irq(usart_dev *dev) { +#ifdef USART_SAFE_INSERT + /* Ignore new bytes if the user defines USART_SAFE_INSERT. */ + rb_safe_insert(dev->rb, (uint8)dev->regs->DR); +#else + /* By default, push bytes around in the ring buffer. */ + rb_push_insert(dev->rb, (uint8)dev->regs->DR); +#endif +} + +void __irq_usart1(void) { + usart_irq(USART1); +} + +void __irq_usart2(void) { + usart_irq(USART2); +} + +void __irq_usart3(void) { + usart_irq(USART3); +} + +#ifdef STM32_HIGH_DENSITY +void __irq_uart4(void) { + usart_irq(UART4); +} + +void __irq_uart5(void) { + usart_irq(UART5); +} +#endif diff --git a/libmaple/usart.h b/libmaple/usart.h index 90b3415..7a93da0 100644 --- a/libmaple/usart.h +++ b/libmaple/usart.h @@ -30,94 +30,293 @@ #ifndef _USART_H_ #define _USART_H_ +#include "libmaple_types.h" +#include "util.h" +#include "rcc.h" +#include "nvic.h" #include "ring_buffer.h" #ifdef __cplusplus extern "C"{ #endif -#define USART_TXE BIT(7) +/* + * Register maps and devices + */ + +/** USART register map type */ +typedef struct usart_reg_map { + __io uint32 SR; /**< Status register */ + __io uint32 DR; /**< Data register */ + __io uint32 BRR; /**< Baud rate register */ + __io uint32 CR1; /**< Control register 1 */ + __io uint32 CR2; /**< Control register 2 */ + __io uint32 CR3; /**< Control register 3 */ + __io uint32 GTPR; /**< Guard time and prescaler register */ +} usart_reg_map; -/* usart device numbers */ -enum { - USART1, - USART2, - USART3, +/** USART1 register map base pointer */ +#define USART1_BASE ((struct usart_reg_map*)0x40013800) +/** USART2 register map base pointer */ +#define USART2_BASE ((struct usart_reg_map*)0x40004400) +/** USART3 register map base pointer */ +#define USART3_BASE ((struct usart_reg_map*)0x40004800) #ifdef STM32_HIGH_DENSITY - UART4, - UART5, +/** UART4 register map base pointer */ +#define UART4_BASE ((struct usart_reg_map*)0x40004C00) +/** UART5 register map base pointer */ +#define UART5_BASE ((struct usart_reg_map*)0x40005000) #endif -}; - -/* peripheral register struct */ -typedef struct usart_port { - volatile uint32 SR; // Status register - volatile uint32 DR; // Data register - volatile uint32 BRR; // Baud rate register - volatile uint32 CR1; // Control register 1 - volatile uint32 CR2; // Control register 2 - volatile uint32 CR3; // Control register 3 - volatile uint32 GTPR; // Guard time and prescaler register -} usart_port; - -/* usart descriptor */ -struct usart_dev { - usart_port *base; - ring_buffer rb; - uint8 rx_buf[64]; - const uint8 rcc_dev_num; - const uint8 nvic_dev_num; -}; - -extern struct usart_dev usart_dev_table[]; + +/* + * Register bit definitions + */ + +/* Status register */ + +#define USART_SR_CTS_BIT 9 +#define USART_SR_LBD_BIT 8 +#define USART_SR_TXE_BIT 7 +#define USART_SR_TC_BIT 6 +#define USART_SR_RXNE_BIT 5 +#define USART_SR_IDLE_BIT 4 +#define USART_SR_ORE_BIT 3 +#define USART_SR_NE_BIT 2 +#define USART_SR_FE_BIT 1 +#define USART_SR_PE_BIT 0 + +#define USART_SR_CTS BIT(USART_SR_CTS_BIT) +#define USART_SR_LBD BIT(USART_SR_LBD_BIT) +#define USART_SR_TXE BIT(USART_SR_TXE_BIT) +#define USART_SR_TC BIT(USART_SR_TC_BIT) +#define USART_SR_RXNE BIT(USART_SR_RXNE_BIT) +#define USART_SR_IDLE BIT(USART_SR_IDLE_BIT) +#define USART_SR_ORE BIT(USART_SR_ORE_BIT) +#define USART_SR_NE BIT(USART_SR_NE_BIT) +#define USART_SR_FE BIT(USART_SR_FE_BIT) +#define USART_SR_PE BIT(USART_SR_PE_BIT) + +/* Data register */ + +#define USART_DR_DR 0xFF + +/* Baud rate register */ + +#define USART_BRR_DIV_MANTISSA (0xFFF << 4) +#define USART_BRR_DIV_FRACTION 0xF + +/* Control register 1 */ + +#define USART_CR1_UE_BIT 13 +#define USART_CR1_M_BIT 12 +#define USART_CR1_WAKE_BIT 11 +#define USART_CR1_PCE_BIT 10 +#define USART_CR1_PS_BIT 9 +#define USART_CR1_PEIE_BIT 8 +#define USART_CR1_TXEIE_BIT 7 +#define USART_CR1_TCIE_BIT 6 +#define USART_CR1_RXNEIE_BIT 5 +#define USART_CR1_IDLEIE_BIT 4 +#define USART_CR1_TE_BIT 3 +#define USART_CR1_RE_BIT 2 +#define USART_CR1_RWU_BIT 1 +#define USART_CR1_SBK_BIT 0 + +#define USART_CR1_UE BIT(USART_CR1_UE_BIT) +#define USART_CR1_M BIT(USART_CR1_M_BIT) +#define USART_CR1_WAKE BIT(USART_CR1_WAKE_BIT) +#define USART_CR1_WAKE_IDLE (0 << USART_CR1_WAKE_BIT) +#define USART_CR1_WAKE_ADDR (1 << USART_CR1_WAKE_BIT) +#define USART_CR1_PCE BIT(USART_CR1_PCE_BIT) +#define USART_CR1_PS BIT(USART_CR1_PS_BIT) +#define USART_CR1_PS_EVEN (0 << USART_CR1_PS_BIT) +#define USART_CR1_PS_ODD (1 << USART_CR1_PS_BIT) +#define USART_CR1_PEIE BIT(USART_CR1_PEIE_BIT) +#define USART_CR1_TXEIE BIT(USART_CR1_TXEIE_BIT) +#define USART_CR1_TCIE BIT(USART_CR1_TCIE_BIT) +#define USART_CR1_RXNEIE BIT(USART_CR1_RXNEIE_BIT) +#define USART_CR1_IDLEIE BIT(USART_CR1_IDLEIE_BIT) +#define USART_CR1_TE BIT(USART_CR1_TE_BIT) +#define USART_CR1_RE BIT(USART_CR1_RE_BIT) +#define USART_CR1_RWU BIT(USART_CR1_RWU_BIT) +#define USART_CR1_RWU_ACTIVE (0 << USART_CR1_RWU_BIT) +#define USART_CR1_RWU_MUTE (1 << USART_CR1_RWU_BIT) +#define USART_CR1_SBK BIT(USART_CR1_SBK_BIT) + +/* Control register 2 */ + +#define USART_CR2_LINEN_BIT 14 +#define USART_CR2_CLKEN_BIT 11 +#define USART_CR2_CPOL_BIT 10 +#define USART_CR2_CPHA_BIT 9 +#define USART_CR2_LBCL_BIT 8 +#define USART_CR2_LBDIE_BIT 6 +#define USART_CR2_LBDL_BIT 5 + +#define USART_CR2_LINEN BIT(USART_CR2_LINEN_BIT) +#define USART_CR2_STOP (0x3 << 12) +#define USART_CR2_STOP_BITS_1 (0x0 << 12) +/* Not on UART4, UART5 */ +#define USART_CR2_STOP_BITS_POINT_5 (0x1 << 12) +/* Not on UART4, UART5 */ +#define USART_CR2_STOP_BITS_1_POINT_5 (0x3 << 12) +#define USART_CR2_STOP_BITS_2 (0x2 << 12) +#define USART_CR2_CLKEN BIT(USART_CR2_CLKEN_BIT) +/* Not on UART4, UART5 */ +#define USART_CR2_CPOL BIT(USART_CR2_CPOL_BIT) +#define USART_CR2_CPOL_LOW (0x0 << USART_CR2_CLKEN_BIT) +#define USART_CR2_CPOL_HIGH (0x1 << USART_CR2_CLKEN_BIT) +/* Not on UART4, UART5 */ +#define USART_CR2_CPHA BIT(USART_CR2_CPHA_BIT) +#define USART_CR2_CPHA_FIRST (0x0 << USART_CR2_CPHA_BIT) +#define USART_CR2_CPHA_SECOND (0x1 << USART_CR2_CPHA_BIT) +/* Not on UART4, UART5 */ +#define USART_CR2_LBCL BIT(USART_CR2_LBCL_BIT) +#define USART_CR2_LBDIE BIT(USART_CR2_LBDIE_BIT) +#define USART_CR2_LBDL BIT(USART_CR2_LBDL_BIT) +#define USART_CR2_LBDL_10_BIT (0 << USART_CR2_LBDL_BIT) +#define USART_CR2_LBDL_11_BIT (1 << USART_CR2_LBDL_BIT) +#define USART_CR2_ADD 0xF + +/* Control register 3 */ + +#define USART_CR3_CTSIE_BIT 10 +#define USART_CR3_CTSE_BIT 9 +#define USART_CR3_RTSE_BIT 8 +#define USART_CR3_DMAT_BIT 7 +#define USART_CR3_DMAR_BIT 6 +#define USART_CR3_SCEN_BIT 5 +#define USART_CR3_NACK_BIT 4 +#define USART_CR3_HDSEL_BIT 3 +#define USART_CR3_IRLP_BIT 2 +#define USART_CR3_IREN_BIT 1 +#define USART_CR3_EIE_BIT 0 + +/* Not on UART4, UART5 */ +#define USART_CR3_CTSIE BIT(USART_CR3_CTSIE_BIT) +/* Not on UART4, UART5 */ +#define USART_CR3_CTSE BIT(USART_CR3_CTSE_BIT) +/* Not on UART4, UART5 */ +#define USART_CR3_RTSE BIT(USART_CR3_RTSE_BIT) +/* Not on UART5 */ +#define USART_CR3_DMAT BIT(USART_CR3_DMAT_BIT) +/* Not on UART5 */ +#define USART_CR3_DMAR BIT(USART_CR3_DMAR_BIT) +/* Not on UART4, UART5 */ +#define USART_CR3_SCEN BIT(USART_CR3_SCEN_BIT) +/* Not on UART4, UART5 */ +#define USART_CR3_NACK BIT(USART_CR3_NACK_BIT) +#define USART_CR3_HDSEL BIT(USART_CR3_HDSEL_BIT) +#define USART_CR3_IRLP BIT(USART_CR3_IRLP_BIT) +#define USART_CR3_IRLP_NORMAL (0 << USART_CR3_IRLP_BIT) +#define USART_CR3_IRLP_LOW_POWER (1 << USART_CR3_IRLP_BIT) +#define USART_CR3_IREN BIT(USART_CR3_IREN_BIT) +#define USART_CR3_EIE BIT(USART_CR3_EIE_BIT) + +/* Guard time and prescaler register */ + +/* Not on UART4, UART5 */ +#define USART_GTPR_GT (0xFF << 8) +/* Not on UART4, UART5 */ +#define USART_GTPR_PSC 0xFF + +/* + * Devices + */ + +#define USART_RX_BUF_SIZE 64 + +/** USART device type */ +typedef struct usart_dev { + usart_reg_map *regs; + ring_buffer *rb; + uint32 max_baud; + uint8 rx_buf[USART_RX_BUF_SIZE]; + rcc_clk_id clk_id; + nvic_irq_num irq_num; +} usart_dev; + +/** USART1 device */ +extern usart_dev *USART1; +/** USART2 device */ +extern usart_dev *USART2; +/** USART3 device */ +extern usart_dev *USART3; +#ifdef STM32_HIGH_DENSITY +/** UART4 device */ +extern usart_dev *UART4; +/** UART5 device */ +extern usart_dev *UART5; +#endif + +#ifdef STM32_MEDIUM_DENSITY +#define NR_USARTS 3 +#elif defined(STM32_HIGH_DENSITY) +#define NR_USARTS 5 +#else +#warn "Only medium and high density devices are currently supported" +#endif + +void usart_init(usart_dev *dev); +void usart_set_baud_rate(usart_dev *dev, uint32 clock_speed, uint32 baud); +void usart_enable(usart_dev *dev); +void usart_disable(usart_dev *dev); +void usart_foreach(void (*fn)(usart_dev *dev)); +void usart_putstr(usart_dev *dev, const char*); +void usart_putudec(usart_dev *dev, uint32 val); /** - * @brief send one character on a usart - * @param usart_num usart to send on - * @param byte byte to send + * @brief Disable all serial ports. */ -static inline void usart_putc(uint8 usart_num, uint8 byte) { - usart_port *port = usart_dev_table[usart_num].base; +static inline void usart_disable_all(void) { + usart_foreach(usart_disable); +} - /* Wait for the buffer to empty */ - while ((port->SR & USART_TXE) == 0) +/** + * @brief Transmit one character on a serial port. + * @param dev Serial port to send on. + * @param byte Byte to transmit. + */ +static inline void usart_putc(usart_dev* dev, uint8 byte) { + usart_reg_map *regs = dev->regs; + + while ((regs->SR & USART_SR_TXE) == 0) ; - port->DR = byte; + regs->DR = byte; } /** - * @brief read one character from a usart - * @param usart_num usart to read from + * @brief Read one character from a serial port. + * + * It's not safe to call this function if the serial port has no data + * available. + * + * @param dev Serial port to read from * @return byte read + * @see usart_data_available() */ -static inline uint8 usart_getc(uint8 usart_num) { - return rb_remove(&usart_dev_table[usart_num].rb); +static inline uint8 usart_getc(usart_dev *dev) { + return rb_remove(dev->rb); } /** - * @brief return the amount of data available in the rx buffer - * @param usart_num which usart to check - * @return number of bytes in the rx buffer + * @brief Return the amount of data available in a serial port's RX buffer. + * @param dev Serial port to check + * @return Number of bytes in dev's RX buffer. */ -static inline uint32 usart_data_available(uint8 usart_num) { - return rb_full_count(&usart_dev_table[usart_num].rb); +static inline uint32 usart_data_available(usart_dev *dev) { + return rb_full_count(dev->rb); } /** - * @brief removes the contents of the rx fifo - * @param usart_num which usart to reset + * @brief Discard the contents of a serial port's RX buffer. + * @param dev Serial port whose buffer to empty. */ -static inline void usart_reset_rx(uint8 usart_num) { - rb_reset(&usart_dev_table[usart_num].rb); +static inline void usart_reset_rx(usart_dev *dev) { + rb_reset(dev->rb); } -void usart_init(uint8 usart_num, uint32 baud); -void usart_disable(uint8 usart_num); -void usart_disable_all(); -void usart_putstr(uint8 usart_num, const char*); -void usart_putudec(uint8 usart_num, uint32 val); - #ifdef __cplusplus } // extern "C" #endif diff --git a/libmaple/util.c b/libmaple/util.c index 77af5b8..4a234ae 100644 --- a/libmaple/util.c +++ b/libmaple/util.c @@ -24,7 +24,7 @@ /** * @brief Utility procedures for debugging, mostly an error LED fade - * and messages dumped over a uart for failed asserts. + * and messages dumped over a UART for failed asserts. */ #include "libmaple.h" @@ -34,38 +34,38 @@ #include "adc.h" #include "timer.h" -/* Failed asserts send out a message on this USART. */ -#ifndef ERROR_USART_NUM -#define ERROR_USART_NUM USART2 +/* Failed ASSERT()s send out a message using this USART config. */ +#ifndef ERROR_USART +#define ERROR_USART USART2 +#define ERROR_USART_CLK_SPEED 72000000UL #define ERROR_USART_BAUD 9600 #define ERROR_TX_PORT GPIOA #define ERROR_TX_PIN 2 #endif /* If you define ERROR_LED_PORT and ERROR_LED_PIN, then a failed - assert will also throb an LED connected to that port an pin. - FIXME this should work together with wirish somehow. */ + * ASSERT() will also throb() an LED connected to that port and pin. + */ #if defined(ERROR_LED_PORT) && defined(ERROR_LED_PIN) #define HAVE_ERROR_LED #endif /** * @brief Disables all peripheral interrupts except USB and fades the - * error LED. - * - * Called from exc.S with global interrupts disabled. + * error LED. */ +/* (Called from exc.S with global interrupts disabled.) */ void __error(void) { /* Turn off peripheral interrupts */ nvic_irq_disable_all(); - /* Turn off timers */ + /* Turn off timers */ timer_disable_all(); /* Turn off ADC */ adc_disable_all(); - /* Turn off all usarts */ + /* Turn off all USARTs */ usart_disable_all(); /* Turn the USB interrupt back on so the bootloader keeps on functioning */ @@ -78,33 +78,33 @@ void __error(void) { } /** - * @brief Prints an error message on a uart upon a failed assertion - * and error throbs. + * @brief Print an error message on a UART upon a failed assertion + * and throb the error LED, if there is one defined. * @param file Source file of failed assertion * @param line Source line of failed assertion * @param exp String representation of failed assertion * @sideeffect Turns of all peripheral interrupts except USB. */ void _fail(const char* file, int line, const char* exp) { - /* Initialize the error usart */ + /* Initialize the error USART */ gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_AF_OUTPUT_PP); - usart_init(ERROR_USART_NUM, ERROR_USART_BAUD); + usart_init(ERROR_USART); + usart_set_baud_rate(ERROR_USART, ERROR_USART_CLK_SPEED, ERROR_USART_BAUD); /* Print failed assert message */ - usart_putstr(ERROR_USART_NUM, "ERROR: FAILED ASSERT("); - usart_putstr(ERROR_USART_NUM, exp); - usart_putstr(ERROR_USART_NUM, "): "); - usart_putstr(ERROR_USART_NUM, file); - usart_putstr(ERROR_USART_NUM, ": "); - usart_putudec(ERROR_USART_NUM, line); - usart_putc(ERROR_USART_NUM, '\n'); - usart_putc(ERROR_USART_NUM, '\r'); + usart_putstr(ERROR_USART, "ERROR: FAILED ASSERT("); + usart_putstr(ERROR_USART, exp); + usart_putstr(ERROR_USART, "): "); + usart_putstr(ERROR_USART, file); + usart_putstr(ERROR_USART, ": "); + usart_putudec(ERROR_USART, line); + usart_putc(ERROR_USART, '\n'); + usart_putc(ERROR_USART, '\r'); /* Error fade */ __error(); } - /** * @brief Fades the error LED on and off * @sideeffect Sets output push-pull on ERROR_LED_PIN. @@ -117,7 +117,7 @@ void throb(void) { uint32 i = 0; gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_OUTPUT_PP); - /* Error fade */ + /* Error fade. */ while (1) { if (CC == TOP_CNT) { slope = -1; @@ -138,9 +138,8 @@ void throb(void) { i++; } #else - /* No error LED is connected; do nothing. */ + /* No error LED is defined; do nothing. */ while (1) ; #endif } - diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp index 8398878..aa8855b 100644 --- a/wirish/comm/HardwareSerial.cpp +++ b/wirish/comm/HardwareSerial.cpp @@ -24,69 +24,85 @@ /** * @file HardwareSerial.cpp - * - * @brief Wiring-like serial api + * @brief Wirish serial port implementation. */ -#include "wirish.h" +#include "gpio.h" +#include "timer.h" + #include "HardwareSerial.h" -#include "usart.h" - -// FIXME: High density device ports, usages of BOARD_USARTx_yX_PIN -// instead of holding onto a gpio_dev, tx_pin, rx_pin, timer_dev, and -// channel_num -- that stuff is all in the PIN_MAP. -HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9, 10, TIMER1, 2); -HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3); -HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10, 11, NULL, 0); - -HardwareSerial::HardwareSerial(uint8 usart_num, - uint32 max_baud, - gpio_dev *gpio_device, +#include "boards.h" + +#define TX1 BOARD_USART1_TX_PIN +#define RX1 BOARD_USART1_RX_PIN +#define TX2 BOARD_USART2_TX_PIN +#define RX2 BOARD_USART2_RX_PIN +#define TX3 BOARD_USART3_TX_PIN +#define RX3 BOARD_USART3_RX_PIN +#if defined STM32_HIGH_DENSITY && !defined(BOARD_maple_RET6) +#define TX4 BOARD_UART4_TX_PIN +#define RX4 BOARD_UART4_RX_PIN +#define TX5 BOARD_UART5_TX_PIN +#define RX5 BOARD_UART5_RX_PIN +#endif + +HardwareSerial Serial1(USART1, TX1, RX1); +HardwareSerial Serial2(USART2, TX2, RX2); +HardwareSerial Serial3(USART3, TX3, RX3); +#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6) +HardwareSerial Serial4(UART4, TX4, RX4); +HardwareSerial Serial5(UART5, TX5, RX5); +#endif + +HardwareSerial::HardwareSerial(usart_dev *usart_device, uint8 tx_pin, - uint8 rx_pin, - timer_dev *timer_device, - uint8 channel_num) { - this->usart_num = usart_num; - this->max_baud = max_baud; - this->gpio_device = gpio_device; + uint8 rx_pin) { + this->usart_device = usart_device; this->tx_pin = tx_pin; this->rx_pin = rx_pin; - this->timer_device = timer_device; - this->channel_num = channel_num; } uint8 HardwareSerial::read(void) { - return usart_getc(usart_num); + return usart_getc(usart_device); } uint32 HardwareSerial::available(void) { - return usart_data_available(usart_num); + return usart_data_available(usart_device); } void HardwareSerial::write(unsigned char ch) { - usart_putc(usart_num, ch); + usart_putc(usart_device, ch); } void HardwareSerial::begin(uint32 baud) { - if (baud > max_baud) { + ASSERT(baud <= usart_device->max_baud); + + if (baud > usart_device->max_baud) { return; } - gpio_set_mode(gpio_device, tx_pin, GPIO_AF_OUTPUT_PP); - gpio_set_mode(gpio_device, rx_pin, GPIO_INPUT_FLOATING); + const stm32_pin_info *txi = &PIN_MAP[tx_pin]; + const stm32_pin_info *rxi = &PIN_MAP[rx_pin]; + + gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING); - if (timer_device != NULL) { - /* turn off any pwm if there's a conflict on this usart */ - timer_set_mode(timer_device, channel_num, TIMER_DISABLED); + if (txi->timer_device != NULL) { + /* Turn off any PWM if there's a conflict on this GPIO bit. */ + timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED); } - usart_init(usart_num, baud); + usart_init(usart_device); + usart_set_baud_rate(usart_device, + CYCLES_PER_MICROSECOND * 1000000UL, + baud); + usart_enable(usart_device); } void HardwareSerial::end(void) { - usart_disable(usart_num); + usart_disable(usart_device); } void HardwareSerial::flush(void) { - usart_reset_rx(usart_num); + usart_reset_rx(usart_device); } diff --git a/wirish/comm/HardwareSerial.h b/wirish/comm/HardwareSerial.h index 7852d51..5e86f79 100644 --- a/wirish/comm/HardwareSerial.h +++ b/wirish/comm/HardwareSerial.h @@ -24,43 +24,33 @@ /** * @file HardwareSerial.h - * - * @brief Wirish interface to hardware serial communications. + * @brief Wirish serial port interface. */ #ifndef _HARDWARESERIAL_H_ #define _HARDWARESERIAL_H_ #include "libmaple_types.h" -#include "gpio.h" -#include "timer.h" +#include "usart.h" #include "Print.h" -/* NB: this class documented "by hand" (i.e., not using Doxygen) in: - - libmaple/docs/source/lang/serial.rst - - If you alter the public HardwareSerial interface, you must update - the documentation accordingly. */ +/* + * IMPORTANT: + * + * This class documented "by hand" (i.e., not using Doxygen) in: + * + * libmaple/docs/source/lang/api/serial.rst + * + * If you alter the public HardwareSerial interface, you MUST update + * the documentation accordingly. + */ class HardwareSerial : public Print { - private: - uint8 usart_num; - uint32 max_baud; - gpio_dev *gpio_device; - uint8 tx_pin; - uint8 rx_pin; - timer_dev *timer_device; - uint8 channel_num; - public: - HardwareSerial(uint8 usart_num, - uint32 max_baud, - gpio_dev *gpio_device, +public: + HardwareSerial(usart_dev *usart_device, uint8 tx_pin, - uint8 rx_pin, - timer_dev *timer_device, - uint8 channel_num); + uint8 rx_pin); void begin(uint32 baud); void end(void); uint32 available(void); @@ -68,10 +58,18 @@ class HardwareSerial : public Print { void flush(void); virtual void write(unsigned char); using Print::write; +private: + usart_dev *usart_device; + uint8 tx_pin; + uint8 rx_pin; }; + extern HardwareSerial Serial1; extern HardwareSerial Serial2; extern HardwareSerial Serial3; -// TODO: high density device ports +#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6) +extern HardwareSerial Serial4; +extern HardwareSerial Serial5; #endif +#endif -- cgit v1.2.3 From fe8fb8a931306a9701a7f7fa96e1880e1c3123bc Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 8 Apr 2011 15:56:14 -0400 Subject: Adding CLOCK_SPEED_MHZ and CLOCK_SPEED_HZ as derived board-specific values. --- docs/source/lang/api/board-values.rst | 6 ++++++ wirish/boards.h | 17 +++++++++++++++-- 2 files changed, 21 insertions(+), 2 deletions(-) (limited to 'wirish') diff --git a/docs/source/lang/api/board-values.rst b/docs/source/lang/api/board-values.rst index 367adbb..d6d78f6 100644 --- a/docs/source/lang/api/board-values.rst +++ b/docs/source/lang/api/board-values.rst @@ -18,6 +18,12 @@ boards. Some example usages are given :ref:`below Constants --------- +- ``CLOCK_SPEED_MHZ``: Clock speed of your board, in megahertz + (MHz). This is the same as ``CYCLES_PER_MICROSECOND``. + +- ``CLOCK_SPEED_HZ``: Clock speed of your board, in hertz (Hz). This + is the same as ``CLOCK_SPEED_MHZ * 1000000``. + - ``CYCLES_PER_MICROSECOND``: Number of CPU cycles per microsecond on your board. diff --git a/wirish/boards.h b/wirish/boards.h index 8df7028..2515c00 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -119,8 +119,7 @@ bool boardUsesPin(uint8 pin); /* Include the appropriate private header from boards/: */ -/* FIXME put boards/ before these paths once you stick make into the - * IDE; current situation is a hack. */ +/* FIXME HACK put boards/ before these paths once IDE uses make. */ #ifdef BOARD_maple #include "maple.h" @@ -136,7 +135,21 @@ bool boardUsesPin(uint8 pin); */ #include "maple_RET6.h" #else +/* + * TODO turn this into a warning so people can: + * + * #include "my_board_config.h" + * #include "wirish.h" + * + * This will enable third-party board support without requiring that + * anybody hack around in libmaple itself. + */ #error "Board type has not been selected correctly." #endif +/* Set derived definitions */ + +#define CLOCK_SPEED_MHZ CYCLES_PER_MICROSECOND +#define CLOCK_SPEED_HZ (CLOCK_SPEED_MHZ * 1000000UL) + #endif -- cgit v1.2.3 From 9ef9a63da80d79352d1029397865893a78e918fb Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 11 Apr 2011 15:52:48 -0400 Subject: USART bugfix. USART refactor commit f6f9a1122706ed336c52c984d76219dee0594487 only worked for USART1. --- libmaple/usart.c | 2 +- wirish/comm/HardwareSerial.cpp | 19 ++++++++++--------- wirish/comm/HardwareSerial.h | 4 +++- 3 files changed, 14 insertions(+), 11 deletions(-) (limited to 'wirish') diff --git a/libmaple/usart.c b/libmaple/usart.c index de808a7..7fe4f53 100644 --- a/libmaple/usart.c +++ b/libmaple/usart.c @@ -99,7 +99,7 @@ void usart_init(usart_dev *dev) { * @brief Configure a serial port's baud rate. * * @param dev Serial port to be configured - * @param clock_speed MCU clock speed, in megahertz. + * @param clock_speed Clock speed, in megahertz. * @param baud Baud rate for transmit/receive. */ void usart_set_baud_rate(usart_dev *dev, uint32 clock_speed, uint32 baud) { diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp index aa8855b..5c9bff6 100644 --- a/wirish/comm/HardwareSerial.cpp +++ b/wirish/comm/HardwareSerial.cpp @@ -46,18 +46,21 @@ #define RX5 BOARD_UART5_RX_PIN #endif -HardwareSerial Serial1(USART1, TX1, RX1); -HardwareSerial Serial2(USART2, TX2, RX2); -HardwareSerial Serial3(USART3, TX3, RX3); +// TODO Put these magic numbers into boards.h #defines +HardwareSerial Serial1(USART1, TX1, RX1, 72000000UL); +HardwareSerial Serial2(USART2, TX2, RX2, 36000000UL); +HardwareSerial Serial3(USART3, TX3, RX3, 36000000UL); #if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6) -HardwareSerial Serial4(UART4, TX4, RX4); -HardwareSerial Serial5(UART5, TX5, RX5); +HardwareSerial Serial4(UART4, TX4, RX4, 36000000UL); +HardwareSerial Serial5(UART5, TX5, RX5, 36000000UL); #endif HardwareSerial::HardwareSerial(usart_dev *usart_device, uint8 tx_pin, - uint8 rx_pin) { + uint8 rx_pin, + uint32 clock_speed) { this->usart_device = usart_device; + this->clock_speed = clock_speed; this->tx_pin = tx_pin; this->rx_pin = rx_pin; } @@ -93,9 +96,7 @@ void HardwareSerial::begin(uint32 baud) { } usart_init(usart_device); - usart_set_baud_rate(usart_device, - CYCLES_PER_MICROSECOND * 1000000UL, - baud); + usart_set_baud_rate(usart_device, clock_speed, baud); usart_enable(usart_device); } diff --git a/wirish/comm/HardwareSerial.h b/wirish/comm/HardwareSerial.h index 5e86f79..934db23 100644 --- a/wirish/comm/HardwareSerial.h +++ b/wirish/comm/HardwareSerial.h @@ -50,7 +50,8 @@ class HardwareSerial : public Print { public: HardwareSerial(usart_dev *usart_device, uint8 tx_pin, - uint8 rx_pin); + uint8 rx_pin, + uint32 clock_speed); void begin(uint32 baud); void end(void); uint32 available(void); @@ -62,6 +63,7 @@ private: usart_dev *usart_device; uint8 tx_pin; uint8 rx_pin; + uint32 clock_speed; }; extern HardwareSerial Serial1; -- cgit v1.2.3 From 7b14b950363f707c40732b4387f2f50711907673 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 12 Apr 2011 00:08:54 -0400 Subject: Doxygen bugfixes. Fixed various Doxygen comment errors. --- libmaple/adc.h | 1 + libmaple/bkp.h | 6 +++--- libmaple/dma.h | 4 ++++ libmaple/ring_buffer.h | 6 +++--- libmaple/timer.h | 9 +++++---- wirish/pwm.h | 3 +++ wirish/wirish_time.h | 2 +- wirish/wirish_types.h | 3 +++ 8 files changed, 23 insertions(+), 11 deletions(-) (limited to 'wirish') diff --git a/libmaple/adc.h b/libmaple/adc.h index 520b982..c6a67a0 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -309,6 +309,7 @@ uint16 adc_read(const adc_dev *dev, uint8 channel); * Defines the total number of conversions in the regular channel * conversion sequence. * + * @param dev ADC device. * @param length Regular channel sequence length, from 1 to 16. */ static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8 length) { diff --git a/libmaple/bkp.h b/libmaple/bkp.h index cea39b6..97edd2a 100644 --- a/libmaple/bkp.h +++ b/libmaple/bkp.h @@ -46,7 +46,7 @@ extern "C" { /** Backup peripheral register map type. */ typedef struct bkp_reg_map { - const uint32 RESERVED1; + const uint32 RESERVED1; ///< Reserved __io uint32 DR1; ///< Data register 1 __io uint32 DR2; ///< Data register 2 __io uint32 DR3; ///< Data register 3 @@ -61,8 +61,8 @@ typedef struct bkp_reg_map { __io uint32 CR; ///< Control register __io uint32 CSR; ///< Control and status register #ifdef STM32_HIGH_DENSITY - const uint32 RESERVED2; - const uint32 RESERVED3; + const uint32 RESERVED2; ///< Reserved + const uint32 RESERVED3; ///< Reserved __io uint32 DR11; ///< Data register 11 __io uint32 DR12; ///< Data register 12 __io uint32 DR13; ///< Data register 13 diff --git a/libmaple/dma.h b/libmaple/dma.h index c763672..7c380d0 100644 --- a/libmaple/dma.h +++ b/libmaple/dma.h @@ -417,6 +417,8 @@ static inline uint8 dma_is_channel_enabled(dma_dev *dev, dma_channel channel) { * If you're attempting to figure out why a DMA interrupt fired; you * may find dma_get_irq_cause() more convenient. * + * @param dev DMA device + * @param channel Channel whose ISR bits to return. * @see dma_get_irq_cause(). */ static inline uint8 dma_get_isr_bits(dma_dev *dev, dma_channel channel) { @@ -430,6 +432,8 @@ static inline uint8 dma_get_isr_bits(dma_dev *dev, dma_channel channel) { * If you're attempting to clean up after yourself in a DMA interrupt, * you may find dma_get_irq_cause() more convenient. * + * @param dev DMA device + * @param channel Channel whose ISR bits to clear. * @see dma_get_irq_cause() */ static inline void dma_clear_isr_bits(dma_dev *dev, dma_channel channel) { diff --git a/libmaple/ring_buffer.h b/libmaple/ring_buffer.h index 101f010..ad6ad96 100644 --- a/libmaple/ring_buffer.h +++ b/libmaple/ring_buffer.h @@ -89,7 +89,7 @@ static inline uint16 rb_full_count(ring_buffer *rb) { /** * @brief Returns true if and only if the ring buffer is full. - * @brief rb Buffer to test. + * @param rb Buffer to test. */ static inline int rb_is_full(ring_buffer *rb) { return (rb->tail + 1 == rb->head) || @@ -139,8 +139,8 @@ static inline int16 rb_safe_remove(ring_buffer *rb) { /** * @brief Attempt to insert an element into a ring buffer. * - * @brief rb Buffer to insert into. - * @brief element Value to insert into rb. + * @param rb Buffer to insert into. + * @param element Value to insert into rb. * @sideeffect If rb is not full, appends element onto buffer. * @return If element was appended, then true; otherwise, false. */ static inline int rb_safe_insert(ring_buffer *rb, uint8 element) { diff --git a/libmaple/timer.h b/libmaple/timer.h index fa19cc9..befc026 100644 --- a/libmaple/timer.h +++ b/libmaple/timer.h @@ -628,8 +628,8 @@ static inline uint16 timer_get_count(timer_dev *dev) { /** * @brief Sets the counter value for the given timer. - * @param timer_num Timer whose counter to set - * @param value New counter value + * @param dev Timer whose counter to set + * @param value New counter value */ static inline void timer_set_count(timer_dev *dev, uint16 value) { (dev->regs).bas->CNT = value; @@ -804,8 +804,8 @@ static inline void timer_cc_disable(timer_dev *dev, uint8 channel) { /** * @brief Get a channel's capture/compare output polarity - * @brief dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. - * @brief channel Channel whose capture/compare output polarity to get. + * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. + * @param channel Channel whose capture/compare output polarity to get. * @return Polarity, either 0 or 1. * @see timer_cc_set_polarity() */ @@ -982,6 +982,7 @@ typedef enum timer_oc_mode_flags { * * @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL. * @param channel Channel to configure in output compare mode. + * @param mode Timer mode to set. * @param flags OR of timer_oc_mode_flags. * @see timer_oc_mode * @see timer_oc_mode_flags diff --git a/wirish/pwm.h b/wirish/pwm.h index a6385e9..4ce4bb4 100644 --- a/wirish/pwm.h +++ b/wirish/pwm.h @@ -43,6 +43,9 @@ * * User code is expected to determine and honor the maximum value * (based on the configured period). + * + * @param pin PWM output pin + * @param duty_cycle Duty cycle to set. */ void pwmWrite(uint8 pin, uint16 duty_cycle); diff --git a/wirish/wirish_time.h b/wirish/wirish_time.h index a0c0c82..a0b1c11 100644 --- a/wirish/wirish_time.h +++ b/wirish/wirish_time.h @@ -23,7 +23,7 @@ *****************************************************************************/ /** - * @file time.h + * @file wirish_time.h * @brief Timing and delay functions. */ diff --git a/wirish/wirish_types.h b/wirish/wirish_types.h index 475f470..39efae0 100644 --- a/wirish/wirish_types.h +++ b/wirish/wirish_types.h @@ -57,6 +57,9 @@ typedef struct stm32_pin_info { uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ } stm32_pin_info; +/** + * Variable attribute, instructs the linker to place the marked + * variable in Flash instead of RAM. */ #define __FLASH__ __attr_flash #endif -- cgit v1.2.3 From 686b7d5a2d72e71bac76bd7ad9f4aae4e95039c5 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 12 Apr 2011 17:17:12 -0400 Subject: Fixing brain-damaged abs() implementation. --- wirish/wirish_math.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/wirish_math.h b/wirish/wirish_math.h index fa544a9..f9062af 100644 --- a/wirish/wirish_math.h +++ b/wirish/wirish_math.h @@ -100,7 +100,7 @@ static inline long map(long value, long fromStart, long fromEnd, #ifdef abs #undef abs #endif -#define abs(x) (((x) > 0) ? (x) : -(unsigned)(x)) +#define abs(x) (((x) > 0) ? (x) : -(x)) /* Following are duplicate declarations (with Doxygen comments) for * some of the math.h functions; this is for the convenience of the -- cgit v1.2.3 From cdd7bb7a13442160fea29e10ddc61402f56f4bd1 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 12 Apr 2011 01:07:59 -0400 Subject: Reverting "Rewrote Print class." This reverts commit 8bd3cebbee62e2dd7e961b149cc8bb0e980eaf88. --- docs/source/lang/api/serial.rst | 35 ++---- docs/source/lang/api/serialusb.rst | 35 ++---- wirish/Print.cpp | 245 ++++++++++++++++--------------------- wirish/Print.h | 87 +++++++------ 4 files changed, 167 insertions(+), 235 deletions(-) (limited to 'wirish') diff --git a/docs/source/lang/api/serial.rst b/docs/source/lang/api/serial.rst index 29c70a2..fadac34 100644 --- a/docs/source/lang/api/serial.rst +++ b/docs/source/lang/api/serial.rst @@ -116,34 +116,25 @@ means that you can use any of these functions on any of ``Serial1``, Print the argument's digits over the USART, in decimal format. -.. cpp:function:: HardwareSerial::print(long long n) +.. cpp:function:: HardwareSerial::print(long n) Print the argument's digits over the USART, in decimal format. Negative values will be prefixed with a ``'-'`` character. -.. cpp:function:: HardwareSerial::print(unsigned long long n) +.. cpp:function:: HardwareSerial::print(unsigned long n) Print the argument's digits over the USART, in decimal format. -.. _lang-serial-print-n-base: +.. cpp:function:: HardwareSerial::print(long n, int base) -.. cpp:function:: HardwareSerial::print(int n, int base) - - Print the digits of ``n`` over the USART, in base ``base``. The - ``base`` value 2 corresponds to binary, 8 to octal, 10 to decimal, - and 16 to hexadecimal (you can also use the symbolic constants - ``BIN``, ``OCT``, ``DEC``, ``HEX``). If ``base`` is 10, negative - values will be prefixed with a ``'-'`` character (otherwise, ``n`` - will be interpreted as an unsigned quantity). - -.. cpp:function:: HardwareSerial::print(long long n, int base) - - Same behavior as the above :ref:`print(int n, int base) - `, except with 64-bit values. + Print the digits of ``n`` over the USART, in base ``base`` (which + may be between 2 and 16). The ``base`` value 2 corresponds to + binary, 8 to octal, 10 to decimal, and 16 to hexadecimal. Negative + values will be prefixed with a ``'-'`` character. .. cpp:function:: HardwareSerial::print(double n) - Print ``n``, accurate to 6 digits after the decimal point. + Print ``n``, accurate to 2 digits after the decimal point. .. _lang-serial-println: @@ -167,19 +158,15 @@ means that you can use any of these functions on any of ``Serial1``, Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: HardwareSerial::println(long long n) +.. cpp:function:: HardwareSerial::println(long n) Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: HardwareSerial::println(unsigned long long n) +.. cpp:function:: HardwareSerial::println(unsigned long n) Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: HardwareSerial::println(int n, int base) - - Like ``print(n, b)``, followed by ``"\r\n"``. - -.. cpp:function:: HardwareSerial::println(long long n, int base) +.. cpp:function:: HardwareSerial::println(long n, int base) Like ``print(n, b)``, followed by ``"\r\n"``. diff --git a/docs/source/lang/api/serialusb.rst b/docs/source/lang/api/serialusb.rst index 4ddfa4a..ee7146e 100644 --- a/docs/source/lang/api/serialusb.rst +++ b/docs/source/lang/api/serialusb.rst @@ -109,35 +109,26 @@ world!")``. Print the argument's digits over the USB connection, in decimal format. -.. cpp:function:: USBSerial::print(long long n) +.. cpp:function:: USBSerial::print(long n) Print the argument's digits over the USB connection, in decimal format. Negative values will be prefixed with a ``'-'`` character. -.. cpp:function:: USBSerial::print(unsigned long long n) +.. cpp:function:: USBSerial::print(unsigned long n) Print the argument's digits over the USB connection, in decimal format. -.. _lang-serial-print-n-base: +.. cpp:function:: USBSerial::print(long n, int base) -.. cpp:function:: USBSerial::print(int n, int base) - - Print the digits of ``n`` over USB, in base ``base``. The ``base`` - value 2 corresponds to binary, 8 to octal, 10 to decimal, and 16 to - hexadecimal (you can also use the symbolic constants ``BIN``, - ``OCT``, ``DEC``, ``HEX``). If ``base`` is 10, negative values - will be prefixed with a ``'-'`` character (otherwise, ``n`` will be - interpreted as an unsigned quantity). - -.. cpp:function:: HardwareSerial::print(long long n, int base) - - Same behavior as the above :ref:`print(int n, int base) - `, except with 64-bit values. + Print the digits of ``n`` over the USB connection, in base ``base`` + (which may be between 2 and 16). The ``base`` value 2 corresponds + to binary, 8 to octal, 10 to decimal, and 16 to hexadecimal. + Negative values will be prefixed with a ``'-'`` character. .. cpp:function:: USBSerial::print(double n) - Print ``n``, accurate to 6 digits after the decimal point. + Print ``n``, accurate to 2 digits after the decimal point. .. _lang-serialusb-println: @@ -161,19 +152,15 @@ world!")``. Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: USBSerial::println(long long n) +.. cpp:function:: USBSerial::println(long n) Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: USBSerial::println(unsigned long long n) +.. cpp:function:: USBSerial::println(unsigned long n) Like ``print(n)``, followed by ``"\r\n"``. -.. cpp:function:: USBSerial::println(int n, int base) - - Like ``print(n, b)``, followed by ``"\r\n"``. - -.. cpp:function:: USBSerial::println(long long n, int base) +.. cpp:function:: USBSerial::println(long n, int base) Like ``print(n, b)``, followed by ``"\r\n"``. diff --git a/wirish/Print.cpp b/wirish/Print.cpp index 9c52321..c66ca61 100644 --- a/wirish/Print.cpp +++ b/wirish/Print.cpp @@ -1,127 +1,91 @@ -/****************************************************************************** - * The MIT License +/* + * Print.cpp - Base class that provides print() and println() + * Copyright (c) 2008 David A. Mellis. All right reserved. * - * Copyright (c) 2011 LeafLabs, LLC. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public License + * as published by the Free Software Foundation; either version 2.1 of + * the License, or (at your option) any later version. * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: + * This library is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA + * 02110-1301 USA * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ + * Modified 23 November 2006 by David A. Mellis + */ +#include "wirish.h" #include "Print.h" -#include -#include -#include - -// We'll allocate character buffers of size INT_BUF_SIZE to hold the -// string representations of numbers; this value ensures that they're -// big enough to accomodate the biggest integral value + null byte. -// -// E.g., consider -(2^63-1) = -9223372036854775807, which is 20 -// characters long, including the minus sign. The other edge cases -// are similar. -// -// (Nonetheless, use snprintf everywhere, just in case of error). -#define INT_BUF_SIZE 21 - -// An IEEE-754 double buys you about 16 digits of precision; there's -// the possibility of minus signs, a decimal point, 'e+'/'e-', etc. -// While the Right Thing is to follow Steele and White, I'm just going -// to double what I consider a safe number of bytes and hope for the -// best. -#define DOUBLE_BUF_SIZE 40 - -static void fillBase(char *buf, int buf_size, int64 n, - uint8 n_real_bits, int base); -static void fillBinary(char *buf, int64 n, int start_bit); -static char baseToFmtSpec(int base); +//------------------------------ Public Methods ------------------------------- void Print::write(const char *str) { - for (const char *c = str; *c != '\0'; c++) { - write(*c); - } + while (*str) + write(*str++); } void Print::write(void *buffer, uint32 size) { - for (uint32 i = 0; i < size; i++) { - write(*((uint8*)buffer + i)); + uint8 *ch = (uint8*)buffer; + while (size--) { + write(*ch++); } } +void Print::print(uint8 b) { + this->write(b); +} + void Print::print(char c) { - print((uint8) c); + print((byte) c); } void Print::print(const char str[]) { write(str); } -void Print::print(uint8 b) { - write(b); -} - -void Print::print(int32 n) { - print(n, DEC); +void Print::print(int n) { + print((long) n); } -void Print::print(uint32 n) { - print((uint64) n); +void Print::print(unsigned int n) { + print((unsigned long) n); } -void Print::print(int64 n) { - print(n, DEC); -} - -void Print::print(uint64 n) { - char buf[INT_BUF_SIZE]; - snprintf(buf, INT_BUF_SIZE, "%llu", n); - write(buf); +void Print::print(long n) { + if (n < 0) { + print('-'); + n = -n; + } + printNumber(n, 10); } -void Print::print(int32 n, int base) { - // Worst case: sign bit set && base == BIN: 32 bytes for digits + - // 1 null (base == BIN means no minus sign). - char buf[33]; - fillBase(buf, sizeof(buf), (int64)n, 32, base); - write(buf); +void Print::print(unsigned long n) { + printNumber(n, 10); } -void Print::print(int64 n, int base) { - // As above, but now 64 bytes for bits + 1 null - char buf[65]; - fillBase(buf, sizeof(buf), n, 64, base); - write(buf); +void Print::print(long n, int base) { + if (base == 0) { + print((char) n); + } else if (base == 10) { + print(n); + } else { + printNumber(n, base); + } } void Print::print(double n) { - char buf[DOUBLE_BUF_SIZE]; - // This breaks strict compliance with the Arduino library behavior - // (which is equivalent to using "%.2f"), but that's really not - // enough. According to Stroustrup, "%f" without precision is - // equivalent to ".6f", which is much better. - snprintf(buf, DOUBLE_BUF_SIZE, "%f", n); - write(buf); + printFloat(n, 2); } void Print::println(void) { - print("\r\n"); + print('\r'); + print('\n'); } void Print::println(char c) { @@ -139,32 +103,27 @@ void Print::println(uint8 b) { println(); } -void Print::println(int32 n) { +void Print::println(int n) { print(n); println(); } -void Print::println(uint32 n) { +void Print::println(unsigned int n) { print(n); println(); } -void Print::println(int64 n) { +void Print::println(long n) { print(n); println(); } -void Print::println(uint64 n) { +void Print::println(unsigned long n) { print(n); println(); } -void Print::println(int32 n, int base) { - print(n, base); - println(); -} - -void Print::println(int64 n, int base) { +void Print::println(long n, int base) { print(n, base); println(); } @@ -174,54 +133,58 @@ void Print::println(double n) { println(); } -// -- Auxiliary functions ----------------------------------------------------- +//------------------------------ Private Methods ------------------------------ -static void fillBase(char *buf, int buf_size, int64 n, - uint8 n_real_bits, int base) { - if (base == BIN) { - fillBinary(buf, n, n_real_bits - 1); - } else { - char spec = baseToFmtSpec(base); - char fmt[5]; - - if (base == BYTE) - n = (uint8)n; - - if (n_real_bits == 32) { - snprintf(fmt, sizeof(fmt), "%%l%c", spec); - snprintf(buf, buf_size, fmt, (int32)n); - } else { - snprintf(fmt, sizeof(fmt), "%%ll%c", spec); - snprintf(buf, buf_size, fmt, n); - } +void Print::printNumber(unsigned long n, uint8 base) { + unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars. + unsigned long i = 0; + + if (n == 0) { + print('0'); + return; } + + while (n > 0) { + buf[i++] = n % base; + n /= base; + } + + for (; i > 0; i--) + print((char) (buf[i - 1] < 10 ? + '0' + buf[i - 1] : + 'A' + buf[i - 1] - 10)); } -// Assumes sizeof(buf) > start_bit. -static void fillBinary(char *buf, int64 n, int start_bit) { - int b = 0; // position in buf - int i = start_bit; // position in n's bits - while(!(n & (1 << i))) { - i--; +void Print::printFloat(double number, uint8 digits) { + // Handle negative numbers + if (number < 0.0) { + print('-'); + number = -number; } - for(; i >= 0; i--) { - buf[b++] = '0' + ((n >> i) & 0x1); + + // Round correctly so that print(1.999, 2) prints as "2.00" + double rounding = 0.5; + for (uint8 i=0; i 0) { + print("."); } - buf[b] = '\0'; -} - -static char baseToFmtSpec(int base) { - switch (base) { - case DEC: - return 'd'; - case HEX: - return 'x'; - case OCT: - return 'o'; - case BYTE: - return 'd'; - default: - // Shouldn't happen, but give a sensible default - return 'd'; + + // Extract digits from the remainder one at a time + while (digits-- > 0) { + remainder *= 10.0; + int toPrint = int(remainder); + print(toPrint); + remainder -= toPrint; } } diff --git a/wirish/Print.h b/wirish/Print.h index 4527948..dc21183 100644 --- a/wirish/Print.h +++ b/wirish/Print.h @@ -1,67 +1,62 @@ -/****************************************************************************** - * The MIT License +/* + * Print.h - Base class that provides print() and println() + * Copyright (c) 2008 David A. Mellis. All right reserved. * - * Copyright (c) 2011 LeafLabs, LLC. + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public License + * as published by the Free Software Foundation; either version 2.1 of + * the License, or (at your option) any later version. * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: + * This library is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA + * 02110-1301 USA. + */ -#ifndef _PRINT_H_ -#define _PRINT_H_ +#ifndef Print_h +#define Print_h -#include "libmaple_types.h" +#include +#include // for size_t -#define DEC 10 -#define HEX 16 -#define OCT 8 -#define BIN 2 -#define BYTE 0 // yuck +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 +#define BYTE 0 -class Print { +class Print +{ + private: + void printNumber(unsigned long, uint8); + void printFloat(double, uint8); public: virtual void write(uint8) = 0; virtual void write(const char *str); - virtual void write(void *buf, uint32 size); - + virtual void write(void *, uint32); void print(char); void print(const char[]); void print(uint8); - void print(int32); - void print(uint32); - void print(int64); - void print(uint64); - void print(int32, int); - void print(int64, int); + void print(int); + void print(unsigned int); + void print(long); + void print(unsigned long); + void print(long, int); void print(double); - void println(void); void println(char); void println(const char[]); void println(uint8); - void println(int32); - void println(uint32); - void println(int64); - void println(uint64); - void println(int32, int); - void println(int64, int); + void println(int); + void println(unsigned int); + void println(long); + void println(unsigned long); + void println(long, int); void println(double); }; -- cgit v1.2.3 From fc3126378e0c13b03b3c5dd886bebb2014878717 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 12 Apr 2011 01:13:52 -0400 Subject: Compromise Print implementation. The users really hated the code size requirements for an snprintf()-based Print implementation, but I really hated how bad the old implementation was. Revised version fixes bugs related to printing 64-bit values and has some improved behavior when it comes to printing doubles. Now, instead of happily printing garbage values when large doubles are printed, we try printing "" or "-" (depending on sign) when the argument is too big for the old strategy to accommodate. --- wirish/Print.cpp | 119 +++++++++++++++++++++++++++++++++++++++++++------------ wirish/Print.h | 40 +++++++++++-------- 2 files changed, 117 insertions(+), 42 deletions(-) (limited to 'wirish') diff --git a/wirish/Print.cpp b/wirish/Print.cpp index c66ca61..3d7e836 100644 --- a/wirish/Print.cpp +++ b/wirish/Print.cpp @@ -18,16 +18,38 @@ * 02110-1301 USA * * Modified 23 November 2006 by David A. Mellis + * Modified 12 April 2011 by Marti Bolivar */ +#include +#include + +#ifndef LLONG_MAX +/* + * Note: + * + * At time of writing (12 April 2011), the limits.h that came with the + * newlib we distributed didn't include LLONG_MAX. Because we're + * staying away from using templates (see /notes/coding_standard.rst, + * "Language Features and Compiler Extensions"), this value was + * copy-pasted from a println() of the value + * + * std::numeric_limits::max(). + */ +#define LLONG_MAX 9223372036854775807LL +#endif + #include "wirish.h" #include "Print.h" -//------------------------------ Public Methods ------------------------------- +/* + * Public methods + */ void Print::write(const char *str) { - while (*str) + while (*str) { write(*str++); + } } void Print::write(void *buffer, uint32 size) { @@ -42,7 +64,7 @@ void Print::print(uint8 b) { } void Print::print(char c) { - print((byte) c); + print((byte)c); } void Print::print(const char str[]) { @@ -50,14 +72,22 @@ void Print::print(const char str[]) { } void Print::print(int n) { - print((long) n); + print((long long)n); } void Print::print(unsigned int n) { - print((unsigned long) n); + print((unsigned long long)n); } void Print::print(long n) { + print((long long)n); +} + +void Print::print(unsigned long n) { + print((unsigned long long)n); +} + +void Print::print(long long n) { if (n < 0) { print('-'); n = -n; @@ -65,13 +95,13 @@ void Print::print(long n) { printNumber(n, 10); } -void Print::print(unsigned long n) { +void Print::print(unsigned long long n) { printNumber(n, 10); } -void Print::print(long n, int base) { +void Print::print(unsigned long long n, int base) { if (base == 0) { - print((char) n); + print((char)n); } else if (base == 10) { print(n); } else { @@ -114,16 +144,26 @@ void Print::println(unsigned int n) { } void Print::println(long n) { - print(n); + print((long long)n); println(); } void Print::println(unsigned long n) { + print((unsigned long long)n); + println(); +} + +void Print::println(long long n) { print(n); println(); } -void Print::println(long n, int base) { +void Print::println(unsigned long long n) { + print(n); + println(); +} + +void Print::println(unsigned long long n, int base) { print(n, base); println(); } @@ -133,10 +173,12 @@ void Print::println(double n) { println(); } -//------------------------------ Private Methods ------------------------------ +/* + * Private methods + */ -void Print::printNumber(unsigned long n, uint8 base) { - unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars. +void Print::printNumber(unsigned long long n, uint8 base) { + unsigned char buf[CHAR_BIT * sizeof(long long)]; unsigned long i = 0; if (n == 0) { @@ -149,30 +191,57 @@ void Print::printNumber(unsigned long n, uint8 base) { n /= base; } - for (; i > 0; i--) - print((char) (buf[i - 1] < 10 ? - '0' + buf[i - 1] : - 'A' + buf[i - 1] - 10)); + for (; i > 0; i--) { + print((char)(buf[i - 1] < 10 ? + '0' + buf[i - 1] : + 'A' + buf[i - 1] - 10)); + } } +/* According to snprintf(), + * + * nextafter((double)numeric_limits::max(), 0.0) ~= 9.22337e+18 + * + * This slightly smaller value was picked semi-arbitrarily. */ +#define LARGE_DOUBLE_TRESHOLD (9.1e18) + +/* THIS FUNCTION SHOULDN'T BE USED IF YOU NEED ACCURATE RESULTS. + * + * This implementation is meant to be simple and not occupy too much + * code size. However, printing floating point values accurately is a + * subtle task, best left to a well-tested library function. + * + * See Steele and White 2003 for more details: + * + * http://kurtstephens.com/files/p372-steele.pdf + */ void Print::printFloat(double number, uint8 digits) { + // Hackish fail-fast behavior for large-magnitude doubles + if (abs(number) >= LARGE_DOUBLE_TRESHOLD) { + if (number < 0.0) { + print('-'); + } + print(""); + return; + } + // Handle negative numbers if (number < 0.0) { print('-'); number = -number; } - // Round correctly so that print(1.999, 2) prints as "2.00" + // Simplistic rounding strategy so that e.g. print(1.999, 2) + // prints as "2.00" double rounding = 0.5; - for (uint8 i=0; i 0) { remainder *= 10.0; - int toPrint = int(remainder); - print(toPrint); - remainder -= toPrint; + int to_print = (int)remainder; + print(to_print); + remainder -= to_print; } } diff --git a/wirish/Print.h b/wirish/Print.h index dc21183..a4a93bf 100644 --- a/wirish/Print.h +++ b/wirish/Print.h @@ -16,29 +16,28 @@ * License along with this library; if not, write to the Free Software * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA * 02110-1301 USA. + * + * Modified 12 April 2011 by Marti Bolivar */ -#ifndef Print_h -#define Print_h +#ifndef _PRINT_H_ +#define _PRINT_H_ #include -#include // for size_t -#define DEC 10 -#define HEX 16 -#define OCT 8 -#define BIN 2 -#define BYTE 0 +enum { + BYTE = 0, + BIN = 2, + OCT = 8, + DEC = 10, + HEX = 16 +}; -class Print -{ - private: - void printNumber(unsigned long, uint8); - void printFloat(double, uint8); - public: +class Print { +public: virtual void write(uint8) = 0; virtual void write(const char *str); - virtual void write(void *, uint32); + virtual void write(void*, uint32); void print(char); void print(const char[]); void print(uint8); @@ -46,7 +45,9 @@ class Print void print(unsigned int); void print(long); void print(unsigned long); - void print(long, int); + void print(long long); + void print(unsigned long long); + void print(unsigned long long, int); void print(double); void println(void); void println(char); @@ -56,8 +57,13 @@ class Print void println(unsigned int); void println(long); void println(unsigned long); - void println(long, int); + void println(long long); + void println(unsigned long long); + void println(unsigned long long, int); void println(double); +private: + void printNumber(unsigned long long, uint8); + void printFloat(double, uint8); }; #endif -- cgit v1.2.3 From de528cc466b39ba05dca170c9a6ed7474c47fbcf Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 13 Apr 2011 15:43:59 -0400 Subject: Updating Maple Native pins for prototype C. --- wirish/boards/maple_native.cpp | 197 +++++++++++++++++++++-------------------- wirish/boards/maple_native.h | 22 ++--- 2 files changed, 110 insertions(+), 109 deletions(-) (limited to 'wirish') diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index 2813e91..adc9497 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -49,116 +49,117 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D3/PB13 */ {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D4/PB14 */ {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D5/PB15 */ - {GPIOC, NULL, ADC1, 0, 0, 10}, /* D6/PC0 */ - {GPIOC, NULL, ADC1, 1, 0, 11}, /* D7/PC1 */ - {GPIOC, NULL, ADC1, 2, 0, 12}, /* D8/PC2 */ - {GPIOC, NULL, ADC1, 3, 0, 13}, /* D9/PC3 */ - {GPIOC, NULL, ADC1, 4, 0, 14}, /* D10/PC4 */ - {GPIOC, NULL, ADC1, 5, 0, 15}, /* D11/PC5 */ - {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D12/PC6 */ - {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D13/PC7 */ - {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D14/PC8 */ - {GPIOC, TIMER8, NULL, 9, 4, ADCx}, /* D15/PC9 */ - {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D16/PC10 */ - {GPIOC, NULL, NULL, 11, 0, ADCx}, /* D17/PC11 */ - {GPIOC, NULL, NULL, 12, 0, ADCx}, /* D18/PC12 */ - {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D19/PC13 */ - {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D20/PC14 */ - {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D21/PC15 */ - {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D22/PA8 */ - {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D23/PA9 */ - {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D24/PA10 */ - {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D25/PB9 */ + {GPIOG, NULL, NULL, 15, 0, ADCx}, /* D6/PG15 (BUT) */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D7/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D8/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D9/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D10/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D11/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D12/PC5 */ + {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D13/PC6 */ + {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D14/PC7 */ + {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D15/PC8 */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx}, /* D16/PC9 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D17/PC10 */ + {GPIOC, NULL, NULL, 11, 0, ADCx}, /* D18/PC11 */ + {GPIOC, NULL, NULL, 12, 0, ADCx}, /* D19/PC12 */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D20/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D21/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D22/PC15 (LED) */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D23/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D24/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D25/PA10 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D26/PB9 */ /* Bottom header */ - /* Note: D{48, 49, 50} are also TIMER2_CH{2, 3, 4}, respectively. */ + /* Note: D{49, 50, 51} are also TIMER2_CH{2, 3, 4}, respectively. */ - {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D26/PD2 */ - {GPIOD, NULL, NULL, 3, 0, ADCx}, /* D27/PD3 */ - {GPIOD, NULL, NULL, 6, 0, ADCx}, /* D28/PD6 */ - {GPIOG, NULL, NULL, 11, 0, ADCx}, /* D29/PG11 */ - {GPIOG, NULL, NULL, 12, 0, ADCx}, /* D30/PG12 */ - {GPIOG, NULL, NULL, 13, 0, ADCx}, /* D31/PG13 */ - {GPIOG, NULL, NULL, 14, 0, ADCx}, /* D32/PG14 */ - {GPIOG, NULL, NULL, 8, 0, ADCx}, /* D33/PG8 */ - {GPIOG, NULL, NULL, 7, 0, ADCx}, /* D34/PG7 */ - {GPIOG, NULL, NULL, 6, 0, ADCx}, /* D35/PG6 */ - {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D36/PB5 */ - {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D37/PB6 */ - {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D38/PB7 */ - {GPIOF, NULL, ADC3, 6, 0, 4}, /* D39/PF6 */ - {GPIOF, NULL, ADC3, 7, 0, 5}, /* D40/PF7 */ - {GPIOF, NULL, ADC3, 8, 0, 6}, /* D41/PF8 */ - {GPIOF, NULL, ADC3, 9, 0, 7}, /* D42/PF9 */ - {GPIOF, NULL, ADC3, 10, 0, 8}, /* D43/PF10 */ - {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D44/PF11 */ - {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D45/PB1 */ - {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D46/PB0 */ - {GPIOA, TIMER5, ADC1, 0, 1, 0}, /* D47/PA0 */ - {GPIOA, TIMER5, ADC1, 1, 2, 1}, /* D48/PA1 */ - {GPIOA, TIMER5, ADC1, 2, 3, 2}, /* D49/PA2 */ - {GPIOA, TIMER5, ADC1, 3, 4, 3}, /* D50/PA3 */ - {GPIOA, NULL, ADC1, 4, 0, 4}, /* D51/PA4 */ - {GPIOA, NULL, ADC1, 5, 0, 5}, /* D52/PA5 */ - {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D53/PA6 */ - {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D54/PA7 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D27/PD2 */ + {GPIOD, NULL, NULL, 3, 0, ADCx}, /* D28/PD3 */ + {GPIOD, NULL, NULL, 6, 0, ADCx}, /* D29/PD6 */ + {GPIOG, NULL, NULL, 11, 0, ADCx}, /* D30/PG11 */ + {GPIOG, NULL, NULL, 12, 0, ADCx}, /* D31/PG12 */ + {GPIOG, NULL, NULL, 13, 0, ADCx}, /* D32/PG13 */ + {GPIOG, NULL, NULL, 14, 0, ADCx}, /* D33/PG14 */ + {GPIOG, NULL, NULL, 8, 0, ADCx}, /* D34/PG8 */ + {GPIOG, NULL, NULL, 7, 0, ADCx}, /* D35/PG7 */ + {GPIOG, NULL, NULL, 6, 0, ADCx}, /* D36/PG6 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D37/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D38/PB6 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D39/PB7 */ + {GPIOF, NULL, ADC3, 6, 0, 4}, /* D40/PF6 */ + {GPIOF, NULL, ADC3, 7, 0, 5}, /* D41/PF7 */ + {GPIOF, NULL, ADC3, 8, 0, 6}, /* D42/PF8 */ + {GPIOF, NULL, ADC3, 9, 0, 7}, /* D43/PF9 */ + {GPIOF, NULL, ADC3, 10, 0, 8}, /* D44/PF10 */ + {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D45/PF11 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D46/PB1 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D47/PB0 */ + {GPIOA, TIMER5, ADC1, 0, 1, 0}, /* D48/PA0 */ + {GPIOA, TIMER5, ADC1, 1, 2, 1}, /* D49/PA1 */ + {GPIOA, TIMER5, ADC1, 2, 3, 2}, /* D50/PA2 */ + {GPIOA, TIMER5, ADC1, 3, 4, 3}, /* D51/PA3 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D52/PA4 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D53/PA5 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D54/PA6 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D55/PA7 */ /* Right (triple) header */ - {GPIOF, NULL, NULL, 0, 0, ADCx}, /* D55/PF0 */ - {GPIOD, NULL, NULL, 11, 0, ADCx}, /* D56/PD11 */ - {GPIOD, NULL, NULL, 14, 0, ADCx}, /* D57/PD14 */ - {GPIOF, NULL, NULL, 1, 0, ADCx}, /* D58/PF1 */ - {GPIOD, NULL, NULL, 12, 0, ADCx}, /* D59/PD12 */ - {GPIOD, NULL, NULL, 15, 0, ADCx}, /* D60/PD15 */ - {GPIOF, NULL, NULL, 2, 0, ADCx}, /* D61/PF2 */ - {GPIOD, NULL, NULL, 13, 0, ADCx}, /* D62/PD13 */ - {GPIOD, NULL, NULL, 0, 0, ADCx}, /* D63/PD0 */ - {GPIOF, NULL, NULL, 3, 0, ADCx}, /* D64/PF3 */ - {GPIOE, NULL, NULL, 3, 0, ADCx}, /* D65/PE3 */ - {GPIOD, NULL, NULL, 1, 0, ADCx}, /* D66/PD1 */ - {GPIOF, NULL, NULL, 4, 0, ADCx}, /* D67/PF4 */ - {GPIOE, NULL, NULL, 4, 0, ADCx}, /* D68/PE4 */ - {GPIOE, NULL, NULL, 7, 0, ADCx}, /* D69/PE7 */ - {GPIOF, NULL, NULL, 5, 0, ADCx}, /* D70/PF5 */ - {GPIOE, NULL, NULL, 5, 0, ADCx}, /* D71/PE5 */ - {GPIOE, NULL, NULL, 8, 0, ADCx}, /* D72/PE8 */ - {GPIOF, NULL, NULL, 12, 0, ADCx}, /* D73/PF12 */ - {GPIOE, NULL, NULL, 6, 0, ADCx}, /* D74/PE6 */ - {GPIOE, NULL, NULL, 9, 0, ADCx}, /* D75/PE9 */ - {GPIOF, NULL, NULL, 13, 0, ADCx}, /* D76/PF13 */ - {GPIOE, NULL, NULL, 10, 0, ADCx}, /* D77/PE10 */ - {GPIOF, NULL, NULL, 14, 0, ADCx}, /* D78/PF14 */ - {GPIOG, NULL, NULL, 9, 0, ADCx}, /* D79/PG9 */ - {GPIOE, NULL, NULL, 11, 0, ADCx}, /* D80/PE11 */ - {GPIOF, NULL, NULL, 15, 0, ADCx}, /* D81/PF15 */ - {GPIOG, NULL, NULL, 10, 0, ADCx}, /* D82/PG10 */ - {GPIOE, NULL, NULL, 12, 0, ADCx}, /* D83/PE12 */ - {GPIOG, NULL, NULL, 0, 0, ADCx}, /* D84/PG0 */ - {GPIOD, NULL, NULL, 5, 0, ADCx}, /* D85/PD5 */ - {GPIOE, NULL, NULL, 13, 0, ADCx}, /* D86/PE13 */ - {GPIOG, NULL, NULL, 1, 0, ADCx}, /* D87/PG1 */ - {GPIOD, NULL, NULL, 4, 0, ADCx}, /* D88/PD4 */ - {GPIOE, NULL, NULL, 14, 0, ADCx}, /* D89/PE14 */ - {GPIOG, NULL, NULL, 2, 0, ADCx}, /* D90/PG2 */ - {GPIOE, NULL, NULL, 1, 0, ADCx}, /* D91/PE1 */ - {GPIOE, NULL, NULL, 15, 0, ADCx}, /* D92/PE15 */ - {GPIOG, NULL, NULL, 3, 0, ADCx}, /* D93/PG3 */ - {GPIOE, NULL, NULL, 0, 0, ADCx}, /* D94/PE0 */ - {GPIOD, NULL, NULL, 8, 0, ADCx}, /* D95/PD8 */ - {GPIOG, NULL, NULL, 4, 0, ADCx}, /* D96/PG4 */ - {GPIOD, NULL, NULL, 9, 0, ADCx}, /* D97/PD9 */ - {GPIOG, NULL, NULL, 5, 0, ADCx}, /* D98/PG5 */ - {GPIOD, NULL, NULL, 10, 0, ADCx} /* D99/PD10 */ + {GPIOF, NULL, NULL, 0, 0, ADCx}, /* D56/PF0 */ + {GPIOD, NULL, NULL, 11, 0, ADCx}, /* D57/PD11 */ + {GPIOD, NULL, NULL, 14, 0, ADCx}, /* D58/PD14 */ + {GPIOF, NULL, NULL, 1, 0, ADCx}, /* D59/PF1 */ + {GPIOD, NULL, NULL, 12, 0, ADCx}, /* D60/PD12 */ + {GPIOD, NULL, NULL, 15, 0, ADCx}, /* D61/PD15 */ + {GPIOF, NULL, NULL, 2, 0, ADCx}, /* D62/PF2 */ + {GPIOD, NULL, NULL, 13, 0, ADCx}, /* D63/PD13 */ + {GPIOD, NULL, NULL, 0, 0, ADCx}, /* D64/PD0 */ + {GPIOF, NULL, NULL, 3, 0, ADCx}, /* D65/PF3 */ + {GPIOE, NULL, NULL, 3, 0, ADCx}, /* D66/PE3 */ + {GPIOD, NULL, NULL, 1, 0, ADCx}, /* D67/PD1 */ + {GPIOF, NULL, NULL, 4, 0, ADCx}, /* D68/PF4 */ + {GPIOE, NULL, NULL, 4, 0, ADCx}, /* D69/PE4 */ + {GPIOE, NULL, NULL, 7, 0, ADCx}, /* D70/PE7 */ + {GPIOF, NULL, NULL, 5, 0, ADCx}, /* D71/PF5 */ + {GPIOE, NULL, NULL, 5, 0, ADCx}, /* D72/PE5 */ + {GPIOE, NULL, NULL, 8, 0, ADCx}, /* D73/PE8 */ + {GPIOF, NULL, NULL, 12, 0, ADCx}, /* D74/PF12 */ + {GPIOE, NULL, NULL, 6, 0, ADCx}, /* D75/PE6 */ + {GPIOE, NULL, NULL, 9, 0, ADCx}, /* D76/PE9 */ + {GPIOF, NULL, NULL, 13, 0, ADCx}, /* D77/PF13 */ + {GPIOE, NULL, NULL, 10, 0, ADCx}, /* D78/PE10 */ + {GPIOF, NULL, NULL, 14, 0, ADCx}, /* D79/PF14 */ + {GPIOG, NULL, NULL, 9, 0, ADCx}, /* D80/PG9 */ + {GPIOE, NULL, NULL, 11, 0, ADCx}, /* D81/PE11 */ + {GPIOF, NULL, NULL, 15, 0, ADCx}, /* D82/PF15 */ + {GPIOG, NULL, NULL, 10, 0, ADCx}, /* D83/PG10 */ + {GPIOE, NULL, NULL, 12, 0, ADCx}, /* D84/PE12 */ + {GPIOG, NULL, NULL, 0, 0, ADCx}, /* D85/PG0 */ + {GPIOD, NULL, NULL, 5, 0, ADCx}, /* D86/PD5 */ + {GPIOE, NULL, NULL, 13, 0, ADCx}, /* D87/PE13 */ + {GPIOG, NULL, NULL, 1, 0, ADCx}, /* D88/PG1 */ + {GPIOD, NULL, NULL, 4, 0, ADCx}, /* D89/PD4 */ + {GPIOE, NULL, NULL, 14, 0, ADCx}, /* D90/PE14 */ + {GPIOG, NULL, NULL, 2, 0, ADCx}, /* D91/PG2 */ + {GPIOE, NULL, NULL, 1, 0, ADCx}, /* D92/PE1 */ + {GPIOE, NULL, NULL, 15, 0, ADCx}, /* D93/PE15 */ + {GPIOG, NULL, NULL, 3, 0, ADCx}, /* D94/PG3 */ + {GPIOE, NULL, NULL, 0, 0, ADCx}, /* D95/PE0 */ + {GPIOD, NULL, NULL, 8, 0, ADCx}, /* D96/PD8 */ + {GPIOG, NULL, NULL, 4, 0, ADCx}, /* D97/PG4 */ + {GPIOD, NULL, NULL, 9, 0, ADCx}, /* D98/PD9 */ + {GPIOG, NULL, NULL, 5, 0, ADCx}, /* D99/PG5 */ + {GPIOD, NULL, NULL, 10, 0, ADCx} /* D100/PD10 */ }; extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { - 12, 13, 14, 15, 22, 23, 24, 25, 37, 38, 45, 46, 47, 48, 49, 50, 53, 54 + 13, 14, 15, 16, 23, 24, 25, 26, 38, 39, 46, 47, 48, 49, 50, 51, 54, 54 }; extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { - 6, 7, 8, 9, 10, 11, 39, 40, 41, 42, 43, 45, 46, 47, 48, 49, 50, 51, 52, 53, - 54 + 7, 8, 9, 10, 11, 12, 40, 41, 42, 43, 44, 46, 47, 48, 49, 50, 51, 52, 53, + 54, 55 }; /* FIXME! see comment by BOARD_NR_USED_PINS in maple_native.h */ diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h index 4e3ee82..10dafa6 100644 --- a/wirish/boards/maple_native.h +++ b/wirish/boards/maple_native.h @@ -43,22 +43,22 @@ #define CYCLES_PER_MICROSECOND 72 #define SYSTICK_RELOAD_VAL 71999 -#define BOARD_LED_PIN 21 -#define BOARD_BUTTON_PIN 18 +#define BOARD_LED_PIN 22 +#define BOARD_BUTTON_PIN 6 #define BOARD_NR_USARTS 5 -#define BOARD_USART1_TX_PIN 25 -#define BOARD_USART1_RX_PIN 26 -#define BOARD_USART2_TX_PIN 51 -#define BOARD_USART2_RX_PIN 52 +#define BOARD_USART1_TX_PIN 26 +#define BOARD_USART1_RX_PIN 27 +#define BOARD_USART2_TX_PIN 52 +#define BOARD_USART2_RX_PIN 53 #define BOARD_USART3_TX_PIN 0 #define BOARD_USART3_RX_PIN 1 -#define BOARD_UART4_TX_PIN 18 -#define BOARD_UART4_RX_PIN 19 -#define BOARD_UART5_TX_PIN 20 -#define BOARD_UART5_RX_PIN 28 +#define BOARD_UART4_TX_PIN 19 +#define BOARD_UART4_RX_PIN 20 +#define BOARD_UART5_TX_PIN 21 +#define BOARD_UART5_RX_PIN 29 -#define BOARD_NR_GPIO_PINS 100 +#define BOARD_NR_GPIO_PINS 101 #define BOARD_NR_PWM_PINS 18 #define BOARD_NR_ADC_PINS 21 /* FIXME! this isn't true at all; almost all of the triple header pins -- cgit v1.2.3 From ac509ea796f907dc27841a1e4cfa74c2a3285d6a Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 25 Apr 2011 18:02:10 -0400 Subject: Minor Print cleanups. --- wirish/Print.cpp | 8 ++++---- wirish/Print.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) (limited to 'wirish') diff --git a/wirish/Print.cpp b/wirish/Print.cpp index 3d7e836..cfb2cda 100644 --- a/wirish/Print.cpp +++ b/wirish/Print.cpp @@ -21,7 +21,8 @@ * Modified 12 April 2011 by Marti Bolivar */ -#include +#include "Print.h" + #include #ifndef LLONG_MAX @@ -39,8 +40,7 @@ #define LLONG_MAX 9223372036854775807LL #endif -#include "wirish.h" -#include "Print.h" +#include "wirish_math.h" /* * Public methods @@ -64,7 +64,7 @@ void Print::print(uint8 b) { } void Print::print(char c) { - print((byte)c); + print((uint8)c); } void Print::print(const char str[]) { diff --git a/wirish/Print.h b/wirish/Print.h index a4a93bf..ec7b163 100644 --- a/wirish/Print.h +++ b/wirish/Print.h @@ -23,7 +23,7 @@ #ifndef _PRINT_H_ #define _PRINT_H_ -#include +#include "libmaple_types.h" enum { BYTE = 0, -- cgit v1.2.3 From 95af192c99459c56bb30763afd93582a524efc3a Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 25 Apr 2011 21:23:00 -0400 Subject: Better debug port support. - gpio.h: afio_mapr_swj_config() renamed afio_cfg_debug_ports() - [new] wirish_debug.h: disableDebugPorts(), enableDebugPorts() - Maple, Maple Native, and Maple RET6 PIN_MAPs are now larger by 5, have mappings for the extra JTAG/SW pins. Documentation was updated appropriately. --- docs/source/hardware/maple.rst | 83 ++++++++++-------------------- docs/source/jtag.rst | 37 +++++++------ docs/source/lang/api/board-values.rst | 22 +++++++- docs/source/lang/api/disabledebugports.rst | 31 +++++++++++ docs/source/lang/api/enabledebugports.rst | 31 +++++++++++ examples/test-session.cpp | 79 ++++++++++++++++++++++++++-- libmaple/gpio.h | 54 ++++++++++++------- wirish/boards/maple.cpp | 13 ++++- wirish/boards/maple.h | 13 ++++- wirish/boards/maple_mini.cpp | 5 +- wirish/boards/maple_mini.h | 6 +++ wirish/boards/maple_native.cpp | 16 ++++-- wirish/boards/maple_native.h | 10 +++- wirish/wirish.h | 1 + wirish/wirish_debug.h | 54 +++++++++++++++++++ 15 files changed, 347 insertions(+), 108 deletions(-) create mode 100644 docs/source/lang/api/disabledebugports.rst create mode 100644 docs/source/lang/api/enabledebugports.rst create mode 100644 wirish/wirish_debug.h (limited to 'wirish') diff --git a/docs/source/hardware/maple.rst b/docs/source/hardware/maple.rst index 44a5238..1fa4f3f 100644 --- a/docs/source/hardware/maple.rst +++ b/docs/source/hardware/maple.rst @@ -40,7 +40,7 @@ Identifying your Rev We went through three versions ("Revs") of the Maple hardware: Rev 1, Rev 3, and Rev 5 [#frev2_4]_; Rev 5, the final design, is currently on sale. The following sections will help you to help you identify your -Rev. Known issues are listed in the :ref:`errata `. +Rev. Rev 5 ^^^^^ @@ -123,46 +123,38 @@ at the command line with :: $ git clone git://github.com/leaflabs/maple.git -.. _maple-errata: +.. _maple-failure-modes: -Errata ------- - -This section lists known issues and warnings for each revision of the -Maple board. The failure modes aren't design errors, but are easy ways -to break or damage your board permanently. For a list of differences -between the Maple and Arduinos, see the :ref:`Arduino Compatibility -reference `. - -The errata are grouped by Maple version ("Rev"). - -Maple Rev 5 -^^^^^^^^^^^ - -Known issues: +Failure Modes +------------- -* **Pin 3 AIN missing**: Pin 3 is capable of analog input, but the - corresponding "AIN" is missing from its silkscreen. - -* **GPIO 39-43 not configured**: this is really more of a software - "TODO" item. Some of the JTAG header pins are numbered 39-43. These - STM32 pins are indeed fully functional :ref:`GPIO ` when a - :ref:`JTAG ` device is not connected, but we have not enabled - them in software and thus they can not be accessed with the regular - :ref:`lang-pinmode` or :ref:`lang-digitalwrite` functions. - -Potential failure modes: +The following known failure modes apply to all Maple versions. The +failure modes aren't design errors, but are easy ways to break or +damage your board permanently. * **High voltage on non-tolerant pins**: not all header pins are 5V compatible; so e.g. connecting certain serial devices in the wrong way could over-voltage the pins. The :ref:`Pin-Mapping Mega Table ` details which pins are 5V-tolerant. -Maple Rev 3 -^^^^^^^^^^^ +Errata +------ + +This section lists known issues and warnings for each revision of the +Maple board. +Rev 5 +^^^^^ Known issues: +* **Pin 3 AIN missing**: Pin 3 is capable of analog input, but on + boards sold in during Fall 2010, the corresponding "AIN" is missing + from its silkscreen. This mistake was fixed in later manufacturing + runs. + +Rev 3 +^^^^^ + * **Bad/Sticky Buttons**: a number of Rev 3 boards sold in May-June 2010 have questionable RESET and BUT buttons. @@ -180,7 +172,7 @@ Known issues: remover we used is "Precision Electronics Cleaner" from RadioShack, which is "Safe on most plastics" and contains Dipropylene glycol monomethyl ether, hydrotreated heavy naphtha, dipropylene glycol - methyl ether acetate (really?), and carbon dioxide. + methyl ether acetate, and carbon dioxide. * **Resistors on pins 0 and 1**: these header pins, which are RX/TX on USART2 (:ref:`Serial2 `), have resistors in-line @@ -192,13 +184,6 @@ Known issues: designs, where they appear to protect the USB-Serial converter from TTL voltage on the headers. -* **GPIO 39-43 not configured**: this is really more of a software - "TODO" item. Some of the JTAG header pins are numbered 39-43. These - STM32 pins are indeed fully functional :ref:`GPIO ` when the a - :ref:`JTAG ` device is not connected, but we have not enabled - them in software and thus they can not be accessed with the regular - :ref:`lang-pinmode` or :ref:`lang-digitalwrite` functions. - * **Silkscreen Errors**: the silkscreen on the bottom indicated PWM functionality on pin 25 and listen the external header GND pin as number 38 (actually 38 is connected to the BUT button). We manually @@ -207,17 +192,8 @@ Known issues: * **PWM Marketing Mistake**: We originally sold the Maple advertising 22 channels of 16-bit hardware PWM; actually the Maple only has 15. -Potential failure modes: - -* **TTL voltage on non-tolerant pins**: not all header pins are 5V - compatible; connecting certain serial devices in the wrong way could - over voltage the pins. The :ref:`Pin-Mapping Mega Table - ` details which pins are 5V-tolerant. - -Maple Rev 1 -^^^^^^^^^^^ - -Known issues: +Rev 1 +^^^^^ * **ADC noise**: generally very high, in particular when the USB port is being used for communications (including keep-alive pings when @@ -248,14 +224,7 @@ Known issues: `_. * **PWM Marketing Mistake**: We originally sold the Maple advertising - 22 channels of 16-bit hardware PWM; actually the Maple only has 15. - -Potential failure modes: - -* **TTL voltage on non-tolerant pins**: not all header pins are 5v - compatible; connecting certain serial devices in the wrong way could - over voltage the pins. The :ref:`Pin-Mapping Mega Table - ` details which pins are 5V-tolerant. + 22 channels of 16-bit hardware PWM; the correct number is 15. Recommended Reading ------------------- diff --git a/docs/source/jtag.rst b/docs/source/jtag.rst index 858021e..cc6d34a 100644 --- a/docs/source/jtag.rst +++ b/docs/source/jtag.rst @@ -1,11 +1,12 @@ +.. highlight:: cpp + .. _jtag: ====== JTAG ====== -.. TODO update adapter schematic, add information on using it with our -.. devices. +.. FIXME update adapter schematic, add better information JTAG is an interface for low-level debugging of digital devices. It gives instruction by instruction control over the microprocessor and @@ -37,32 +38,36 @@ Wiring Diagram to connect a standard 20-pin ARM JTAG device to the 8-pin JTAG port on the Maple. -The Maple has holes for a 8-pin JTAG header but that header is not -soldered on by default. If you know ahead of time that you'll be -needing it, and you order `straight from LeafLabs -`_, add a comment to your order and we can -probably solder one on for no charge. Otherwise, you can simply -attach standard 0.1" pitch male header pins (either the exact 4x2 -block or two 4-pin pieces of breakaway straight header). For a one-off -usage hack, the header can be jammed in the holes and twisted to -ensure electrical contact. +The Maple has holes for a 8-pin JTAG header, but that header is not +soldered on. To use JTAG, simply solder on standard 0.1" pitch male +header pins (either the exact 4 by 2 block, or two 4-pin pieces of +straight breakaway header). Compatible Devices ------------------ We have had good experience with the `Olimex ARM-USB-OCD `_ device, which costs -about 55 euro plus shipping (as of November 2010). +about €55 plus shipping (as of April 2011). + +Function Reference +------------------ + +You can disable or enable the JTAG and Serial Wire debugging ports in +software using the ``disableDebugPorts()`` and ``enableDebugPorts()`` +functions. + +* :ref:`lang-disabledebugports` +* :ref:`lang-enabledebugports` Recommended Reading ------------------- * `Wikipedia Article on Joint Test Action Group (JTAG) `_ -* `STM32/gdb/OpenOCD HOWTO `_ +* `STM32, GDB, OpenOCD How To `_ * STMicro documentation for STM32F103RB microcontroller: * `Datasheet `_ (pdf) * `Reference Manual `_ (pdf) -* There's a `thread on JTAG - `_ in our `forum`_ - which you may find useful. +* `LeafLabs Wiki JTAG How To `_ +* `Forum thread on JTAG `_ diff --git a/docs/source/lang/api/board-values.rst b/docs/source/lang/api/board-values.rst index d6d78f6..e274163 100644 --- a/docs/source/lang/api/board-values.rst +++ b/docs/source/lang/api/board-values.rst @@ -84,8 +84,25 @@ Constants * ``BOARD_NR_USARTS``: Number of serial ports on the board. This number includes UARTs 4 and 5 if they are available. +.. _lang-board-values-debug: + +- Debug (JTAG, SW-Debug) related constants: ``BOARD_JTMS_SWDIO_PIN``, + ``BOARD_JTCK_SWCLK_PIN``, ``BOARD_JTDI_PIN``, ``BOARD_JTDO_PIN``, + and ``BOARD_NJTRST_PIN``. + + These constants are the pin numbers for :ref:`GPIOs ` used by + the :ref:`jtag` and Serial-Wire Debug peripherals. Except for the + Maple Mini, these pins are usually reserved for special purposes by + default (i.e., they are in :ref:`boardUsedPins + `). However, they can be used as + ordinary GPIOs if you call the :ref:`lang-disabledebugports` + function. (Be careful with this on the Maple, as writing to + ``BOARD_NJTRST_PIN`` may cause your board to reset!). + .. _lang-board-values-pwm-pins: + .. _lang-board-values-adc-pins: + .. _lang-board-values-used-pins: Pin Arrays @@ -94,8 +111,7 @@ Pin Arrays Some :ref:`arrays ` of pin numbers are available which you can use to find out certain important information about a given pin. -.. TODO add links to the board-specific hardware information on what -.. are in these arrays +.. TODO [0.1.0] links to board-specific hardware information - ``boardPWMPins``: Pin numbers of each pin capable of :ref:`PWM ` output, using :ref:`pwmWrite() `. The total @@ -159,3 +175,5 @@ See Also - :ref:`lang-toggleled` - :ref:`lang-analogread` - :ref:`lang-pwmwrite` +- :ref:`lang-enabledebugports` +- :ref:`lang-disabledebugports` diff --git a/docs/source/lang/api/disabledebugports.rst b/docs/source/lang/api/disabledebugports.rst new file mode 100644 index 0000000..43ac337 --- /dev/null +++ b/docs/source/lang/api/disabledebugports.rst @@ -0,0 +1,31 @@ +.. highlight:: cpp + +.. _lang-disabledebugports: + +disableDebugPorts() +=================== + +Used to disable the JTAG and Serial Wire debugging ports. + +Library Documentation +--------------------- + +.. doxygenfunction:: disableDebugPorts + +Example +------- + + :: + + void setup() { + disableDebugPorts(); + } + + void loop() { + // Now you can use the debug port pins as ordinary pins + } + +See Also +-------- + +* :ref:`lang-enabledebugports` diff --git a/docs/source/lang/api/enabledebugports.rst b/docs/source/lang/api/enabledebugports.rst new file mode 100644 index 0000000..bee2b0a --- /dev/null +++ b/docs/source/lang/api/enabledebugports.rst @@ -0,0 +1,31 @@ +.. highlight:: cpp + +.. _lang-enabledebugports: + +enableDebugPorts() +================== + +Used to enable the JTAG and Serial Wire debugging ports. + +Library Documentation +--------------------- + +.. doxygenfunction:: enableDebugPorts + +Example +------- + + :: + + void setup() { + enableDebugPorts(); + // Now you can debug using JTAG and SW-Debug + } + + void loop() { + } + +See Also +-------- + +* :ref:`lang-disabledebugports` diff --git a/examples/test-session.cpp b/examples/test-session.cpp index d97d0ca..1d9daf0 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -27,8 +27,10 @@ void cmd_serial1_echo(void); void cmd_gpio_monitoring(void); void cmd_sequential_adc_reads(void); void cmd_gpio_qa(void); -void cmd_sequential_gpio_writes(void); +void cmd_sequential_gpio_toggling(void); void cmd_gpio_toggling(void); +void cmd_sequential_debug_gpio_toggling(void); +void cmd_debug_gpio_toggling(void); void cmd_but_test(void); void cmd_sequential_pwm_test(void); void cmd_servo_sweep(void); @@ -148,13 +150,21 @@ void loop () { break; case 'g': - cmd_sequential_gpio_writes(); + cmd_sequential_gpio_toggling(); break; case 'G': cmd_gpio_toggling(); break; + case 'j': + cmd_sequential_debug_gpio_toggling(); + break; + + case 'J': + cmd_debug_gpio_toggling(); + break; + case 'B': cmd_but_test(); break; @@ -266,6 +276,8 @@ void cmd_print_help(void) { SerialUSB.println("\tU: dump data as fast as possible on USB"); SerialUSB.println("\tg: toggle GPIOs sequentially"); SerialUSB.println("\tG: toggle GPIOs at the same time"); + SerialUSB.println("\tj: toggle debug port GPIOs sequentially"); + SerialUSB.println("\tJ: toggle debug port GPIOs simultaneously"); SerialUSB.println("\tB: test the built-in button"); SerialUSB.println("\tf: toggle pin 4 as fast as possible in bursts"); SerialUSB.println("\tr: monitor and print GPIO status changes"); @@ -534,7 +546,7 @@ void cmd_gpio_qa(void) { } } -void cmd_sequential_gpio_writes(void) { +void cmd_sequential_gpio_toggling(void) { SerialUSB.println("Sequentially toggling all unused pins. " "Press any key for next pin, ESC to stop."); @@ -582,6 +594,67 @@ void cmd_gpio_toggling(void) { } } +uint8 debugGPIOPins[] = {BOARD_JTMS_SWDIO_PIN, + BOARD_JTCK_SWCLK_PIN, + BOARD_JTDI_PIN, + BOARD_JTDO_PIN, + BOARD_NJTRST_PIN}; + +#define N_DEBUG_PINS 5 + +void cmd_sequential_debug_gpio_toggling(void) { + SerialUSB.println("Toggling all debug (JTAG/SWD) pins sequentially. " + "This will permanently disable debug port " + "functionality."); + disableDebugPorts(); + + for (int i = 0; i < N_DEBUG_PINS; i++) { + pinMode(debugGPIOPins[i], OUTPUT); + } + + for (int i = 0; i < N_DEBUG_PINS; i++) { + int pin = debugGPIOPins[i]; + SerialUSB.print("Toggling pin "); + SerialUSB.print(pin, DEC); + SerialUSB.println("..."); + + pinMode(pin, OUTPUT); + do { + togglePin(pin); + } while (!SerialUSB.available()); + + digitalWrite(pin, LOW); + if (SerialUSB.read() == ESC) + break; + } + + for (int i = 0; i < N_DEBUG_PINS; i++) { + digitalWrite(debugGPIOPins[i], 0); + } +} + +void cmd_debug_gpio_toggling(void) { + SerialUSB.println("Toggling debug GPIO simultaneously. " + "This will permanently disable JTAG and Serial Wire " + "debug port functionality. " + "Press any key to stop."); + disableDebugPorts(); + + for (uint32 i = 0; i < N_DEBUG_PINS; i++) { + pinMode(debugGPIOPins[i], OUTPUT); + } + + while (!SerialUSB.available()) { + for (uint32 i = 0; i < N_DEBUG_PINS; i++) { + togglePin(debugGPIOPins[i]); + } + } + + for (uint32 i = 0; i < N_DEBUG_PINS; i++) { + digitalWrite(debugGPIOPins[i], LOW); + } +} + void cmd_but_test(void) { SerialUSB.println("Press the button to test. Press any key to stop."); pinMode(BOARD_BUTTON_PIN, INPUT); diff --git a/libmaple/gpio.h b/libmaple/gpio.h index ec31cc0..353f965 100644 --- a/libmaple/gpio.h +++ b/libmaple/gpio.h @@ -22,7 +22,7 @@ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE * SOFTWARE. - *****************************************************************************/ +*****************************************************************************/ /** * @file gpio.h @@ -261,22 +261,23 @@ typedef struct afio_reg_map { #define AFIO_EVCR_PIN_15 0xF /* AF remap and debug I/O configuration register */ -#define AFIO_MAPR_SWJ_FULL_SWJ (0x0 << 24) -#define AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (0x1 << 24) -#define AFIO_MAPR_SWJ_NO_JTAG_SW (0x2 << 24) -#define AFIO_MAPR_SWJ_NO_JTAG_NO_SW (0x4 << 24) +#define AFIO_MAPR_SWJ_CFG (0x7 << 24) +#define AFIO_MAPR_SWJ_CFG_FULL_SWJ (0x0 << 24) +#define AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST (0x1 << 24) +#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24) +#define AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW (0x4 << 24) #define AFIO_MAPR_ADC2_ETRGREG_REMAP BIT(20) #define AFIO_MAPR_ADC2_ETRGINJ_REMAP BIT(19) #define AFIO_MAPR_ADC1_ETRGREG_REMAP BIT(18) #define AFIO_MAPR_ADC1_ETRGINJ_REMAP BIT(17) #define AFIO_MAPR_TIM5CH4_IREMAP BIT(16) #define AFIO_MAPR_PD01_REMAP BIT(15) -#define AFIO_MAPR_CAN_REMAP (BIT(14) | BIT(13)) -#define AFIO_MAPR_TIM4_REMAP_FULL BIT(12) -#define AFIO_MAPR_TIM3_REMAP (BIT(11) | BIT(10)) -#define AFIO_MAPR_TIM2_REMAP (BIT(9) | BIT(8)) -#define AFIO_MAPR_TIM1_REMAP (BIT(7) | BIT(6)) -#define AFIO_MAPR_USART3_REMAP (BIT(5) | BIT(4)) +#define AFIO_MAPR_CAN_REMAP (0x3 << 13) +#define AFIO_MAPR_TIM4_REMAP BIT(12) +#define AFIO_MAPR_TIM3_REMAP (0x3 << 10) +#define AFIO_MAPR_TIM2_REMAP (0x3 << 8) +#define AFIO_MAPR_TIM1_REMAP (0x3 << 6) +#define AFIO_MAPR_USART3_REMAP (0x3 << 4) #define AFIO_MAPR_USART2_REMAP BIT(3) #define AFIO_MAPR_USART1_REMAP BIT(2) #define AFIO_MAPR_I2C1_REMAP BIT(1) @@ -322,17 +323,32 @@ void afio_init(void); void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port); /** - * Set the SWJ_CONFIG bits in the AFIO MAPR register. + * @brief Debug port configuration * - * @param config Desired SWJ_CONFIG bits setting. One of: - * AFIO_MAPR_SWJ_FULL_SWJ (full SWJ), - * AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (full SWJ, no NJTRST), - * AFIO_MAPR_SWJ_NO_JTAG_SW (JTAG-DP disabled, SW-DP enabled), - * AFIO_MAPR_SWJ_NO_JTAG_NO_SW (JTAG-DP and SW-DP both disabled). + * Used to configure the behavior of JTAG and Serial Wire (SW) debug + * ports and their associated GPIO pins. */ -static inline void afio_mapr_swj_config(uint32 config) { +typedef enum afio_debug_cfg { + AFIO_DEBUG_FULL_SWJ = AFIO_MAPR_SWJ_CFG_FULL_SWJ, /**< + Full Serial Wire and JTAG debug */ + AFIO_DEBUG_FULL_SWJ_NO_NJRST = AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST, /**< + Full Serial Wire and JTAG, but no NJTRST. */ + AFIO_DEBUG_SW_ONLY = AFIO_MAPR_SWJ_CFG_NO_JTAG_SW, /**< + Serial Wire debug only (JTAG-DP disabled, + SW-DP enabled) */ + AFIO_DEBUG_NONE = AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW /**< + No debug; all JTAG and SW pins are free + for use as GPIOs. */ +} afio_debug_cfg; + +/** + * @brief Enable or disable the JTAG and SW debug ports. + * @param config Desired debug port configuration + * @see afio_debug_cfg + */ +static inline void afio_cfg_debug_ports(afio_debug_cfg config) { __io uint32 *mapr = &AFIO_BASE->MAPR; - *mapr = (*mapr & ~(0x7 << 24)) | config; + *mapr = (*mapr & ~AFIO_MAPR_SWJ_CFG) | config; } #ifdef __cplusplus diff --git a/wirish/boards/maple.cpp b/wirish/boards/maple.cpp index 5122290..2d35e7b 100644 --- a/wirish/boards/maple.cpp +++ b/wirish/boards/maple.cpp @@ -88,7 +88,15 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOC, NULL, NULL, 6, 0, ADCx}, /* D35/PC6 */ {GPIOC, NULL, NULL, 7, 0, ADCx}, /* D36/PC7 */ {GPIOC, NULL, NULL, 8, 0, ADCx}, /* D37/PC8 */ - {GPIOC, NULL, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, NULL, NULL, 9, 0, ADCx}, /* D38/PC9 (BUT) */ + + /* JTAG header */ + + {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D39/PA13 */ + {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D40/PA14 */ + {GPIOA, NULL, NULL, 15, 0, ADCx}, /* D41/PA15 */ + {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D42/PB3 */ + {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D43/PB4 */ }; extern const uint8 boardPWMPins[] __FLASH__ = { @@ -100,7 +108,8 @@ extern const uint8 boardADCPins[] __FLASH__ = { }; extern const uint8 boardUsedPins[] __FLASH__ = { - BOARD_LED_PIN, BOARD_BUTTON_PIN + BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN, + BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN }; #endif diff --git a/wirish/boards/maple.h b/wirish/boards/maple.h index 1867de8..4a4465c 100644 --- a/wirish/boards/maple.h +++ b/wirish/boards/maple.h @@ -54,7 +54,7 @@ /* Total number of GPIO pins that are broken out to headers and * intended for general use. */ -#define BOARD_NR_GPIO_PINS 39 +#define BOARD_NR_GPIO_PINS 44 /* Number of pins capable of PWM output */ #define BOARD_NR_PWM_PINS 16 @@ -64,6 +64,15 @@ /* Number of pins already connected to external hardware. For Maple, * these are just BOARD_LED_PIN and BOARD_BUTTON_PIN. */ -#define BOARD_NR_USED_PINS 2 +#define BOARD_NR_USED_PINS 7 + +/* + * Debug port pins + */ +#define BOARD_JTMS_SWDIO_PIN 39 +#define BOARD_JTCK_SWCLK_PIN 40 +#define BOARD_JTDI_PIN 41 +#define BOARD_JTDO_PIN 42 +#define BOARD_NJTRST_PIN 43 #endif diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp index cd2827d..02d62c7 100644 --- a/wirish/boards/maple_mini.cpp +++ b/wirish/boards/maple_mini.cpp @@ -32,13 +32,14 @@ #include "maple_mini.h" #include "gpio.h" +#include "wirish_debug.h" #ifdef BOARD_maple_mini /* Since we want the Serial Wire/JTAG pins as GPIOs, disable both SW * and JTAG debug support */ void boardInit(void) { - afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); + disableDebugPorts(); } extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { @@ -89,7 +90,7 @@ extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { }; extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { - 3, 4, 5, 6, 7, 8, 9, 10, 11, 33 // NB 33 is LED + 3, 4, 5, 6, 7, 8, 9, 10, 11, 33 // NB: 33 is BOARD_LED_PIN }; #define USB_DP 23 diff --git a/wirish/boards/maple_mini.h b/wirish/boards/maple_mini.h index 8b7ae64..3df1da8 100644 --- a/wirish/boards/maple_mini.h +++ b/wirish/boards/maple_mini.h @@ -59,4 +59,10 @@ #define BOARD_NR_ADC_PINS 10 #define BOARD_NR_USED_PINS 4 +#define BOARD_JTMS_SWDIO_PIN 22 +#define BOARD_JTCK_SWCLK_PIN 21 +#define BOARD_JTDI_PIN 20 +#define BOARD_JTDO_PIN 19 +#define BOARD_NJTRST_PIN 18 + #endif diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index adc9497..0b25bd4 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -72,7 +72,8 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D26/PB9 */ /* Bottom header */ - /* Note: D{49, 50, 51} are also TIMER2_CH{2, 3, 4}, respectively. */ + /* Note: D{48, 49, 50, 51} are also TIMER2_CH{1, 2, 3, 4}, respectively. */ + /* TODO remap timer 2 in boardInit(); make the appropriate changes here */ {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D27/PD2 */ {GPIOD, NULL, NULL, 3, 0, ADCx}, /* D28/PD3 */ @@ -150,7 +151,15 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOG, NULL, NULL, 4, 0, ADCx}, /* D97/PG4 */ {GPIOD, NULL, NULL, 9, 0, ADCx}, /* D98/PD9 */ {GPIOG, NULL, NULL, 5, 0, ADCx}, /* D99/PG5 */ - {GPIOD, NULL, NULL, 10, 0, ADCx} /* D100/PD10 */ + {GPIOD, NULL, NULL, 10, 0, ADCx}, /* D100/PD10 */ + + /* JTAG header */ + + {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D101/PA13 */ + {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D102/PA14 */ + {GPIOA, NULL, NULL, 15, 0, ADCx}, /* D103/PA15 */ + {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D104/PB3 */ + {GPIOB, NULL, NULL, 4, 0, ADCx} /* D105/PB4 */ }; extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { @@ -164,7 +173,8 @@ extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { /* FIXME! see comment by BOARD_NR_USED_PINS in maple_native.h */ extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { - BOARD_LED_PIN, BOARD_BUTTON_PIN + BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN, + BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN }; #endif diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h index 10dafa6..13df153 100644 --- a/wirish/boards/maple_native.h +++ b/wirish/boards/maple_native.h @@ -58,12 +58,18 @@ #define BOARD_UART5_TX_PIN 21 #define BOARD_UART5_RX_PIN 29 -#define BOARD_NR_GPIO_PINS 101 +#define BOARD_NR_GPIO_PINS 106 #define BOARD_NR_PWM_PINS 18 #define BOARD_NR_ADC_PINS 21 /* FIXME! this isn't true at all; almost all of the triple header pins * are used by the FSMC by default. Fix this (and the corresponding * boardUsedPins definition in maple_native.cpp) by QA time. */ -#define BOARD_NR_USED_PINS 2 +#define BOARD_NR_USED_PINS 7 + +#define BOARD_JTMS_SWDIO_PIN 101 +#define BOARD_JTCK_SWCLK_PIN 102 +#define BOARD_JTDI_PIN 103 +#define BOARD_JTDO_PIN 104 +#define BOARD_NJTRST_PIN 105 #endif diff --git a/wirish/wirish.h b/wirish/wirish.h index 4cc142d..d30ad20 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -39,6 +39,7 @@ #include "bits.h" #include "pwm.h" #include "ext_interrupts.h" +#include "wirish_debug.h" #include "wirish_math.h" #include "wirish_time.h" #include "HardwareSPI.h" diff --git a/wirish/wirish_debug.h b/wirish/wirish_debug.h new file mode 100644 index 0000000..d4c0bab --- /dev/null +++ b/wirish/wirish_debug.h @@ -0,0 +1,54 @@ +/****************************************************************************** + * The MIT License + * + * Copyright (c) 2011 LeafLabs, LLC. + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + *****************************************************************************/ + +/** + * @file wirish_debug.h + * @brief High level debug port configuration + */ + +/** + * @brief Disable the JTAG and Serial Wire (SW) debug ports. + * + * You can call this function in order to use the JTAG and SW debug + * pins as ordinary GPIOs. + * + * @see enableDebugPorts() + */ +static inline void disableDebugPorts(void) { + afio_cfg_debug_ports(AFIO_DEBUG_NONE); +} + +/** + * @brief Enable the JTAG and Serial Wire (SW) debug ports. + * + * After you call this function, the JTAG and SW debug pins will no + * longer be usable as GPIOs. + * + * @see disableDebugPorts() + */ +static inline void enableDebugPorts(void) { + afio_cfg_debug_ports(AFIO_DEBUG_FULL_SWJ); +} -- cgit v1.2.3 From 90c649c4b36dfc0c80d41878721c06187ada6b90 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Tue, 26 Apr 2011 03:27:33 -0400 Subject: Removing Maple-specific values from WirinPinMode doxygen comment. Comment changes only. --- wirish/io.h | 11 ----------- 1 file changed, 11 deletions(-) (limited to 'wirish') diff --git a/wirish/io.h b/wirish/io.h index 137377d..ace40f2 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -38,17 +38,6 @@ /** * Specifies a GPIO pin behavior. - * - * Each of the GPIO pins on a Maple board may be configured using - * pinMode() to behave in a number of ways: as a digital output pin, - * or as an analog input pin, etc., depending on the particular pin. - * - * This enum specifies the complete set of possible configurations; - * not every pin can have all of these modes. For example, on the - * Maple, pin 15 may be configured as INPUT_ANALOG, but not as PWM. - * See your board's documentation and silkscreen for more information - * on what functionality is available on each pin. - * * @see pinMode() */ typedef enum WiringPinMode { -- cgit v1.2.3 From 033bf3f26290c41074cf487549233ea2c25120f0 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 27 Apr 2011 15:32:31 -0400 Subject: RET6 fixes --- examples/test-session.cpp | 4 ++-- wirish/boards/maple_RET6.cpp | 13 +++++++++++-- wirish/boards/maple_RET6.h | 10 ++++++++-- 3 files changed, 21 insertions(+), 6 deletions(-) (limited to 'wirish') diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 1d9daf0..ad3cacb 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -855,7 +855,7 @@ void enable_usarts(void) { Serial1.begin(BAUD); Serial2.begin(BAUD); Serial3.begin(BAUD); -#ifdef STM32_HIGH_DENSITY +#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6) Serial4.begin(BAUD); Serial5.begin(BAUD); #endif @@ -865,7 +865,7 @@ void disable_usarts(void) { Serial1.end(); Serial2.end(); Serial3.end(); -#ifdef STM32_HIGH_DENSITY +#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6) Serial4.end(); Serial5.end(); #endif diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6.cpp index fd67459..d5d3d32 100644 --- a/wirish/boards/maple_RET6.cpp +++ b/wirish/boards/maple_RET6.cpp @@ -85,7 +85,15 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D35/PC6 */ {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D36/PC7 */ {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D37/PC8 */ - {GPIOC, TIMER8, NULL, 9, 4, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx}, /* D38/PC9 (BUT) */ + + /* JTAG header */ + + {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D39/PA13 */ + {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D40/PA14 */ + {GPIOA, NULL, NULL, 15, 0, ADCx}, /* D41/PA15 */ + {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D42/PB3 */ + {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D43/PB4 */ }; extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { @@ -97,7 +105,8 @@ extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { }; extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { - BOARD_LED_PIN, BOARD_BUTTON_PIN + BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN, + BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN }; #endif diff --git a/wirish/boards/maple_RET6.h b/wirish/boards/maple_RET6.h index d91a4de..97e609d 100644 --- a/wirish/boards/maple_RET6.h +++ b/wirish/boards/maple_RET6.h @@ -55,9 +55,15 @@ #define BOARD_USART3_TX_PIN 29 #define BOARD_USART3_RX_PIN 30 -#define BOARD_NR_GPIO_PINS 39 +#define BOARD_NR_GPIO_PINS 44 #define BOARD_NR_PWM_PINS 16 #define BOARD_NR_ADC_PINS 15 -#define BOARD_NR_USED_PINS 2 +#define BOARD_NR_USED_PINS 7 + +#define BOARD_JTMS_SWDIO_PIN 39 +#define BOARD_JTCK_SWCLK_PIN 40 +#define BOARD_JTDI_PIN 41 +#define BOARD_JTDO_PIN 42 +#define BOARD_NJTRST_PIN 43 #endif -- cgit v1.2.3 From ea6cf3e622350963e25dae21b03b01b13af53ebc Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 27 Apr 2011 17:38:55 -0400 Subject: maple_native.cpp updates/fixes. --- wirish/boards/maple_native.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) (limited to 'wirish') diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index 0b25bd4..ab8b282 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -44,7 +44,7 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { /* Top header */ {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D0/PB10 */ - {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D1/PB2 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D1/PB11 */ {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D2/PB12 */ {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D3/PB13 */ {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D4/PB14 */ @@ -88,12 +88,12 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D37/PB5 */ {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D38/PB6 */ {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D39/PB7 */ - {GPIOF, NULL, ADC3, 6, 0, 4}, /* D40/PF6 */ - {GPIOF, NULL, ADC3, 7, 0, 5}, /* D41/PF7 */ - {GPIOF, NULL, ADC3, 8, 0, 6}, /* D42/PF8 */ - {GPIOF, NULL, ADC3, 9, 0, 7}, /* D43/PF9 */ - {GPIOF, NULL, ADC3, 10, 0, 8}, /* D44/PF10 */ - {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D45/PF11 */ + {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D40/PF11 */ + {GPIOF, NULL, ADC3, 6, 0, 4}, /* D41/PF6 */ + {GPIOF, NULL, ADC3, 7, 0, 5}, /* D42/PF7 */ + {GPIOF, NULL, ADC3, 8, 0, 6}, /* D43/PF8 */ + {GPIOF, NULL, ADC3, 9, 0, 7}, /* D44/PF9 */ + {GPIOF, NULL, ADC3, 10, 0, 8}, /* D45/PF10 */ {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D46/PB1 */ {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D47/PB0 */ {GPIOA, TIMER5, ADC1, 0, 1, 0}, /* D48/PA0 */ @@ -163,11 +163,11 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { }; extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = { - 13, 14, 15, 16, 23, 24, 25, 26, 38, 39, 46, 47, 48, 49, 50, 51, 54, 54 + 13, 14, 15, 16, 23, 24, 25, 26, 38, 39, 46, 47, 48, 49, 50, 51, 54, 55 }; extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { - 7, 8, 9, 10, 11, 12, 40, 41, 42, 43, 44, 46, 47, 48, 49, 50, 51, 52, 53, + 7, 8, 9, 10, 11, 12, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55 }; -- cgit v1.2.3 From 7cd5350622f5c7c84662beaee5b92a362be0f59b Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Thu, 28 Apr 2011 13:52:58 -0400 Subject: SPI refactor. Still a polling driver, but the libmaple proper interface exposes enough that users enable the various interrupts and define their own IRQ handlers if they feel like it. Wirish HardwareSPI interface was largely redone; it's more like the Arduino implementation now, although there are some differences when I didn't like their API. The old methods are still there, but are deprecated and slated for deletion in 0.1.0. New board-specific values: BOARD_NR_SPI, BOARD_SPIx_NSS_PIN, BOARD_SPIx_MOSI_PIN, BOARD_SPIx_MISO_PIN, and BOARD_SPIx_SCK_PIN, for x from 1 to BOARD_NR_SPI. Documentation was updated appropriately. --- docs/source/lang/api/hardwarespi.rst | 215 +++++++-------- docs/source/spi.rst | 6 +- examples/test-spi-roundtrip.cpp | 197 ++++++++++++++ libmaple/spi.c | 333 ++++++++++++++--------- libmaple/spi.h | 495 +++++++++++++++++++++++++++++------ wirish/boards/maple.h | 13 + wirish/boards/maple_RET6.h | 10 + wirish/boards/maple_mini.h | 10 + wirish/boards/maple_native.cpp | 2 +- wirish/boards/maple_native.h | 21 +- wirish/comm/HardwareSPI.cpp | 335 ++++++++++++++++++------ wirish/comm/HardwareSPI.h | 178 +++++++++++-- 12 files changed, 1389 insertions(+), 426 deletions(-) create mode 100644 examples/test-spi-roundtrip.cpp (limited to 'wirish') diff --git a/docs/source/lang/api/hardwarespi.rst b/docs/source/lang/api/hardwarespi.rst index 53a225d..289ded5 100644 --- a/docs/source/lang/api/hardwarespi.rst +++ b/docs/source/lang/api/hardwarespi.rst @@ -5,160 +5,161 @@ HardwareSPI =========== -This class is used for creating objects to manage the Maple's built-in -SPI ports. The Maple has two SPI ports. The relevant pins -corresponding to each port's logic signals are documented in the -following table (and on the Maple silkscreen): +This page describes how to use the built-in SPI ports. It does not +describe the SPI protocol itself. For more information about SPI, see +the :ref:`SPI reference `. -.. _lang-hardwarespi-pinout: +.. contents:: Contents + :local: -.. list-table:: - :header-rows: 1 +Getting Started +--------------- - * - Port number - - NSS - - MOSI - - MISO - - SCK +.. TODO [0.1.0] Add a note about calling disableDebugPorts() when +.. using SPI3 on Maple Native - * - 1 - - 10 - - 11 - - 12 - - 13 +In order to get started, you'll first need to define a ``HardwareSPI`` +variable, which you'll use to control the SPI port. Do this by +putting the line "``HardwareSPI spi(number);``" with your variables, +where ``number`` is the SPI port's number. - * - 2 - - 31 - - 32 - - 33 - - 34 +Here's an example (we'll fill in :ref:`setup() ` and +:ref:`loop() ` later):: -If you use a SPI port, you cannot simultaneously use its associated -pins for other purposes. + // Use SPI port number 1 + HardwareSPI spi(1); -Library Documentation ---------------------- + void setup() { + // Your setup code + } + + void loop() { + // Do stuff with SPI + } -Using the SPI Class -^^^^^^^^^^^^^^^^^^^ +Turning the SPI Port On +----------------------- -You can declare that you want to use SPI in your sketch by putting -``HardwareSPI Spi(number);`` with your variables, where ``number`` is -1 or 2, depending on which SPI you want to use. Then you can use the -functions described in the next section. For example:: +Now it's time to turn your SPI port on. Do this with the ``begin()`` +function (an example is given below). - // Use SPI 1 - HardwareSpi Spi(1); +.. FIXME [0.0.10] Breathe doesn't include the class; fix & submit pull req + +.. doxygenfunction:: HardwareSPI::begin + +The speed at which the SPI port communicates is configured using a +``SPIFrequency`` value: + +.. FIXME [0.1.0] Breathe's enum output is enormous; shrink & submit pull req + +.. doxygenenum:: SPIFrequency + +.. note:: Due to hardware issues, you can't use the frequency + ``SPI_140_625KHz`` with SPI port 1. + +You'll need to determine the correct values for ``frequency``, +``bitOrder``, and ``mode`` yourself, by consulting the datasheet for +the device you're communicating with. Continuing our example from +before, we'll add a call to ``begin()`` to our ``setup()``:: + + // Use SPI port number 1 + HardwareSPI spi(1); void setup() { - Spi.begin(SPI_18MHZ); + // Turn on the SPI port + spi.begin(SPI_18MHZ, MSBFIRST, 0); } void loop() { - // Get the next byte from the peripheral - uint8 byte = Spi.recv(); + // Do stuff with SPI } -HardwareSPI Class Reference -^^^^^^^^^^^^^^^^^^^^^^^^^^^ +If you call ``begin()`` with no arguments (as in "``spi.begin();``"), +it's the same as if you wrote "``spi.begin(SPI_1_125MHZ, MSBFIRST, +0);``". -.. cpp:class:: HardwareSPI +Communicating Over SPI +---------------------- - Class for interacting with SPI. +Now that you've got your SPI port set up, it's time to start +communicating. You can send data using ``HardwareSPI::write()``, +receive data using ``HardwareSPI::read()``, and do both using +``HardwareSPI::transfer()``. -.. cpp:function:: HardwareSPI::HardwareSPI(uint32 spi_num) +.. cpp:function:: void HardwareSPI::write(byte data) - Construct an object for managing a SPI peripheral. ``spi_num`` - must be 1 or 2; see the :ref:`table above - ` for pinout information. + Send a single byte of data. -.. cpp:function:: void HardwareSPI::begin(SPIFrequency freq, uint32 endianness, uint32 mode) + **Parameters**: - Configure the baudrate of the given SPI port and set up the header - pins appropriately. + - ``data``: Byte to send - Parameters: +.. cpp:function:: byte HardwareSPI::read() - - ``freq``: one of the ``SPIFrequency`` values, given :ref:`below - `. + Get the next available, unread byte. If there aren't any unread + bytes, this function will wait until one is received. - - ``endianness``: either ``LSBFIRST`` (little-endian) or - ``MSBFIRST`` (big-endian). +.. cpp:function:: byte HardwareSPI::transmit(byte data) - - ``mode``: one of 0, 1, 2, or 3, and specifies which SPI mode is - used. The mode number determines a combination of polarity and - phase according to the following table: + Send a byte, then return the next byte received. - .. list-table:: - :header-rows: 1 + **Parameters:** - * - Mode - - Polarity - - Phase + - ``data``: Byte to send - * - 0 - - 0 - - 0 + **Returns:** Next unread byte - * - 1 - - 0 - - 1 +Continuing our example from before, let's send a number over SPI and +print out whatever we get back over :ref:`lang-serialusb`:: - * - 2 - - 1 - - 0 + // Use SPI port number 1 + HardwareSPI spi(1); - * - 3 - - 1 - - 1 + void setup() { + // Turn on the SPI port + spi.begin(SPI_18MHZ, MSBFIRST, 0); + } - For more information on polarity and phase, see the - :ref:`external references, below `. + void loop() { + // Send 245 over SPI, and wait for a response. + spi.write(245); + byte response = spi.read(); + // Print out the response received. + SerialUSB.print("response: "); + SerialUSB.println(response, DEC); + } + +HardwareSPI Class Reference +--------------------------- + +There are a number of other things you can accomplish with your +``spi`` object. A full function listing follows. -.. cpp:function:: void HardwareSPI::begin() +.. doxygenclass:: HardwareSPI + :members: HardwareSPI, begin, beginSlave, end, read, write, transfer - A convenience ``begin()``, equivalent to ``begin(SPI_1_125MHZ, - MSBFIRST, 0)``. +Deprecated Functions +-------------------- -.. cpp:function:: uint8 HardwareSpi::send(uint8 *data, uint32 length) +The following functions are defined for now, but they have been +deprecated, and will be removed in a future Maple IDE release. You +shouldn't use them in new programs, and you should change any of your +programs which do use them to the up-to-date functions discussed +above. + +.. cpp:function:: uint8 HardwareSPI::send(uint8 *data, uint32 length) Writes ``data`` into the port buffer to be transmitted as soon as possible, where ``length`` is the number of bytes to send from ``data``. Returns the last byte shifted back from slave. -.. cpp:function:: uint8 HardwareSpi::send(uint8 data) +.. cpp:function:: uint8 HardwareSPI::send(uint8 data) Writes the single byte ``data`` into the port buffer to be transmitted as soon as possible. Returns the data byte shifted back from the slave. -.. cpp:function:: uint8 HardwareSpi::recv() +.. cpp:function:: uint8 HardwareSPI::recv() Reads a byte from the peripheral. Returns the next byte in the buffer. - -SPI Speeds -^^^^^^^^^^ - -.. _lang-hardwarespi-spifrequency: - -The possible SPI speeds are configured using the ``SPIFrequency`` enum: - -.. doxygenenum:: SPIFrequency - -.. _lang-hardwarespi-seealso: - -See Also --------- - -* `Wikipedia Article on Serial Peripheral Interface Bus (SPI) - `_ -* `Arduino reference on SPI - `_ -* `Hardcore SPI on Arduino `_ by kik64 -* STMicro documentation for STM32F103RB microcontroller: - - * `Datasheet `_ (pdf) - * `Reference Manual `_ (pdf) - - diff --git a/docs/source/spi.rst b/docs/source/spi.rst index 2da4bf8..dd9f1f5 100644 --- a/docs/source/spi.rst +++ b/docs/source/spi.rst @@ -8,12 +8,8 @@ The Serial Peripheral Interface Bus (SPI) is a serial data transfer protocol useful for interacting with a wide variety of hardware peripherals. -The Maple has two SPI ports. The first has NSS on D10, MOSI on -D11, MISO on D12, and SCK on D13. The second has NSS on D31, SCK on -D32, MISO on D33, and MOSI on D34. - The public libmaple API for managing the SPI ports is the -:ref:`HardwareSpi ` class. +:ref:`HardwareSPI ` class. Recommended Reading ------------------- diff --git a/examples/test-spi-roundtrip.cpp b/examples/test-spi-roundtrip.cpp new file mode 100644 index 0000000..257303b --- /dev/null +++ b/examples/test-spi-roundtrip.cpp @@ -0,0 +1,197 @@ +/* + * Polling SPI loopback test. + * + * Bob is nowhere to be found, so Alice decides to talk to herself. + * + * Instructions: Connect SPI2 (Alice) to herself (i.e., MISO to MOSI). + * Connect to Alice via Serial2 at 115200 baud. Press any key to start. + * + * Alice will talk to herself for a little while. The sketch will + * report if Alice can't hear anything she says. She'll then start + * talking forever at various frequencies, bit orders, and modes. Use + * an oscilloscope to make sure she's not trying to lie about any of + * those things. + * + * This file is released into the public domain. + * + * Author: Marti Bolivar + */ + +#include "wirish.h" + +HardwareSPI alice(2); + +#define NFREQS 8 +const SPIFrequency spi_freqs[] = { + SPI_140_625KHZ, + SPI_281_250KHZ, + SPI_562_500KHZ, + SPI_1_125MHZ, + SPI_2_25MHZ, + SPI_4_5MHZ, + SPI_9MHZ, + SPI_18MHZ, +}; + +#define TEST_BUF_SIZE 10 +uint8 test_buf[TEST_BUF_SIZE] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; + +void bad_assert(const char* file, int line, const char* exp) { + Serial2.println(); + Serial2.print("ERROR: FAILED ASSERT("); + Serial2.print(exp); + Serial2.print("): "); + Serial2.print(file); + Serial2.print(": "); + Serial2.println(line); + throb(); +} + +#undef ASSERT +#define ASSERT(exp) \ + if (exp) { \ + } else { \ + bad_assert(__FILE__, __LINE__, #exp); \ + } + +void haveConversation(uint32 bitOrder); +void soliloquies(uint32 bitOrder); + +void setup() { + pinMode(BOARD_LED_PIN, OUTPUT); + Serial2.begin(115200); + Serial2.println(); + Serial2.print("** SPI test ready. Press any key to start."); + while (!Serial2.available()) + ; + Serial2.read(); +} + +void loop() { + Serial2.println("** Having a conversation, MSB first"); + haveConversation(MSBFIRST); + + Serial2.println("** Having a conversation, LSB first"); + haveConversation(LSBFIRST); + + Serial2.println(); + Serial2.println("*** All done! It looks like everything worked."); + Serial2.println(); + + Serial2.println("** Alice will now wax eloquent in various styles. " + "Press any key for the next configuration."); + soliloquies(MSBFIRST); + soliloquies(LSBFIRST); + + while (true) + ; +} + +void printFrequencyString(SPIFrequency frequency); +void chat(SPIFrequency frequency, uint32 bitOrder, uint32 mode); + +void haveConversation(uint32 bitOrder) { + for (int f = 0; f < NFREQS; f++) { + for (int mode = 0; mode < 4; mode++) { + chat(spi_freqs[f], bitOrder, mode); + delay(10); + } + } +} + +void chat(SPIFrequency frequency, uint32 bitOrder, uint32 mode) { + Serial2.print("Having a chat.\tFrequency: "); + printFrequencyString(frequency); + Serial2.print(",\tbitOrder: "); + Serial2.print(bitOrder == MSBFIRST ? "MSB" : "LSB"); + Serial2.print(",\tmode: "); + Serial2.print(mode); + Serial2.print("."); + + Serial2.print(" [1] "); + alice.begin(frequency, bitOrder, mode); + + Serial2.print(" [2] "); + uint32 txed = 0; + while (txed < TEST_BUF_SIZE) { + ASSERT(alice.transfer(test_buf[txed]) == test_buf[txed]); + txed++; + } + + Serial2.print(" [3] "); + alice.end(); + + Serial2.println(" ok."); +} + +void soliloquy(SPIFrequency freq, uint32 bitOrder, uint32 mode); + +void soliloquies(uint32 bitOrder) { + for (int f = 0; f < NFREQS; f++) { + for (int mode = 0; mode < 4; mode++) { + soliloquy(spi_freqs[f], bitOrder, mode); + } + } +} + +void soliloquy(SPIFrequency frequency, uint32 bitOrder, uint32 mode) { + const uint8 repeat = 0xAE; + Serial2.print("Alice is giving a soliloquy (repeating 0x"); + Serial2.print(repeat, HEX); + Serial2.print("). Frequency: "); + printFrequencyString(frequency); + Serial2.print(", bitOrder: "); + Serial2.print(bitOrder == MSBFIRST ? "big-endian" : "little-endian"); + Serial2.print(", SPI mode: "); + Serial2.println(mode); + + alice.begin(frequency, bitOrder, mode); + while (!Serial2.available()) { + alice.write(repeat); + delayMicroseconds(200); + } + Serial2.read(); +} + +void printFrequencyString(SPIFrequency frequency) { + switch (frequency) { + case SPI_18MHZ: + Serial2.print("18 MHz"); + break; + case SPI_9MHZ: + Serial2.print("9 MHz"); + break; + case SPI_4_5MHZ: + Serial2.print("4.5 MHz"); + break; + case SPI_2_25MHZ: + Serial2.print("2.25 MHZ"); + break; + case SPI_1_125MHZ: + Serial2.print("1.125 MHz"); + break; + case SPI_562_500KHZ: + Serial2.print("562.500 KHz"); + break; + case SPI_281_250KHZ: + Serial2.print("281.250 KHz"); + break; + case SPI_140_625KHZ: + Serial2.print("140.625 KHz"); + break; + } +} + +// Force init to be called *first*, i.e. before static object allocation. +// Otherwise, statically allocated objects that need libmaple may fail. +__attribute__((constructor)) void premain() { + init(); +} + +int main(void) { + setup(); + while (true) { + loop(); + } + return 0; +} diff --git a/libmaple/spi.c b/libmaple/spi.c index 7bdc18a..2fbc2ac 100644 --- a/libmaple/spi.c +++ b/libmaple/spi.c @@ -3,161 +3,250 @@ * * Copyright (c) 2010 Perry Hung. * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. *****************************************************************************/ /** - * @brief libmaple serial peripheral interface (SPI) definitions - * - * Initial implementation for the SPI interface. - * - * This driver implements only the bare essentials of a polling driver at the - * moment. Master mode only, 8-bit data frames, and polling. - * - * The caller is responsible for controlling the chip select line. - * - * TODO: interrupt based driver, DMA. - * + * @file spi.c + * @author Marti Bolivar + * @brief Serial Peripheral Interface (SPI) support. + * Currently, there is no Integrated Interchip Sound (I2S) support. */ -#include "libmaple.h" -#include "gpio.h" -#include "rcc.h" #include "spi.h" +#include "bitband.h" -typedef struct spi_dev { - SPI *base; - gpio_dev *gpio_d; - uint8 sck_pin; - uint8 miso_pin; - uint8 mosi_pin; -} spi_dev; - -spi_dev spi_dev1 = { - .base = (SPI*)SPI1_BASE, - .gpio_d = NULL, - .sck_pin = 5, - .miso_pin = 6, - .mosi_pin = 7 -}; +/* + * SPI devices + */ -spi_dev spi_dev2 = { - .base = (SPI*)SPI2_BASE, - .gpio_d = NULL, - .sck_pin = 13, - .miso_pin = 14, - .mosi_pin = 15 +static spi_dev spi1 = { + .regs = SPI1_BASE, + .clk_id = RCC_SPI1, + .irq_num = NVIC_SPI1, }; +spi_dev *SPI1 = &spi1; -static void spi_gpio_cfg(const spi_dev *dev); +static spi_dev spi2 = { + .regs = SPI2_BASE, + .clk_id = RCC_SPI2, + .irq_num = NVIC_SPI2, +}; +spi_dev *SPI2 = &spi2; -/** - * @brief Initialize a spi peripheral - * @param spi_num which spi to turn on, SPI1 or SPI2? - * @param prescale prescale factor on the input clock. - * @param endian data frame format (LSBFIRST?) - * @param mode SPI mode number - */ -void spi_init(uint32 spi_num, - uint32 prescale, - uint32 endian, - uint32 mode) { - ASSERT(spi_num == 1 || spi_num == 2); - ASSERT(mode < 4); - - SPI *spi; - uint32 cr1 = 0; - - switch (spi_num) { - case 1: - /* limit to 18 mhz max speed */ - ASSERT(prescale != CR1_BR_PRESCALE_2); - spi = (SPI*)SPI1_BASE; - rcc_clk_enable(RCC_SPI1); - spi_dev1.gpio_d = GPIOA; - spi_gpio_cfg(&spi_dev1); - break; - case 2: - spi = (SPI*)SPI2_BASE; - rcc_clk_enable(RCC_SPI2); - spi_dev1.gpio_d = GPIOB, - spi_gpio_cfg(&spi_dev2); - break; - } +#ifdef STM32_HIGH_DENSITY +static spi_dev spi3 = { + .regs = SPI3_BASE, + .clk_id = RCC_SPI3, + .irq_num = NVIC_SPI3, +}; +spi_dev *SPI3 = &spi3; +#endif - cr1 = prescale | endian | mode | CR1_MSTR | CR1_SSI | CR1_SSM; - spi->CR1 = cr1; +/* + * SPI convenience routines + */ - /* Peripheral enable */ - spi->CR1 |= CR1_SPE; +/** + * @brief Initialize and reset a SPI device. + * @param dev Device to initialize and reset. + */ +void spi_init(spi_dev *dev) { + rcc_clk_enable(dev->clk_id); + rcc_reset_dev(dev->clk_id); } /** - * @brief SPI synchronous 8-bit write, blocking. - * @param spi_num which spi to send on - * @return data shifted back from the slave + * @brief Configure GPIO bit modes for use as a SPI bus master's pins. + * @param nss_dev NSS pin's GPIO device + * @param comm_dev SCK, MISO, MOSI pins' GPIO device + * @param nss_bit NSS pin's GPIO bit on nss_dev + * @param sck_bit SCK pin's GPIO bit on comm_dev + * @param miso_bit MISO pin's GPIO bit on comm_dev + * @param mosi_bit MOSI pin's GPIO bit on comm_dev */ -uint8 spi_tx_byte(uint32 spi_num, uint8 data) { - SPI *spi; +void spi_master_gpio_cfg(gpio_dev *nss_dev, + gpio_dev *comm_dev, + uint8 nss_bit, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit) { + gpio_set_mode(nss_dev, nss_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, sck_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, miso_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, mosi_bit, GPIO_AF_OUTPUT_PP); +} - spi = (spi_num == 1) ? (SPI*)SPI1_BASE : (SPI*)SPI2_BASE; +/** + * @brief Configure GPIO bit modes for use as a SPI bus slave's pins. + * @param nss_dev NSS pin's GPIO device + * @param comm_dev SCK, MISO, MOSI pins' GPIO device + * @param nss_bit NSS pin's GPIO bit on nss_dev + * @param sck_bit SCK pin's GPIO bit on comm_dev + * @param miso_bit MISO pin's GPIO bit on comm_dev + * @param mosi_bit MOSI pin's GPIO bit on comm_dev + */ +void spi_slave_gpio_cfg(gpio_dev *nss_dev, + gpio_dev *comm_dev, + uint8 nss_bit, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit) { + gpio_set_mode(nss_dev, nss_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, sck_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, miso_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, mosi_bit, GPIO_INPUT_FLOATING); +} - while (!(spi->SR & SR_TXE)) - ; +static void spi_reconfigure(spi_dev *dev, uint32 cr1_config); - spi->DR = data; +/** + * @brief Configure and enable a SPI device as bus master. + * + * The device's peripheral will be disabled before being reconfigured. + * + * @param dev Device to configure as bus master + * @param baud Bus baud rate + * @param mode SPI mode + * @param flags Logical OR of spi_cfg_flag values. + * @see spi_cfg_flag + */ +void spi_master_enable(spi_dev *dev, + spi_baud_rate baud, + spi_mode mode, + uint32 flags) { + spi_reconfigure(dev, baud | flags | SPI_CR1_MSTR | mode); +} - while (!(spi->SR & SR_RXNE)) - ; +/** + * @brief Configure and enable a SPI device as a bus slave. + * + * The device's peripheral will be disabled before being reconfigured. + * + * @param dev Device to configure as a bus slave + * @param mode SPI mode + * @param flags Logical OR of spi_cfg_flag values. + * @see spi_cfg_flag + */ +void spi_slave_enable(spi_dev *dev, spi_mode mode, uint32 flags) { + spi_reconfigure(dev, flags | mode); +} - return spi->DR; +/** + * @brief Nonblocking SPI transmit. + * @param dev SPI port to use for transmission + * @param buf Buffer to transmit. The sizeof buf's elements are + * inferred from the dev's data frame format (i.e., are + * correctly treated as 8-bit or 16-bit quantities). + * @param len Maximum number of elements to transmit. + * @return Number of elements transmitted. + */ +uint32 spi_tx(spi_dev *dev, const void *buf, uint32 len) { + spi_reg_map *regs = dev->regs; + uint32 txed = 0; + if (spi_dff(dev) == SPI_DFF_16_BIT) { + const uint8 *buf8 = (const uint8*)buf; + while ((regs->SR & SPI_SR_TXE) && (txed < len)) { + regs->DR = buf8[txed++]; + } + } else { + const uint16 *buf16 = (const uint16*)buf; + while ((regs->SR & SPI_SR_TXE) && (txed < len)) { + regs->DR = buf16[txed++]; + } + } + return txed; } -uint8 spi_tx(uint32 spi_num, uint8 *buf, uint32 len) { - SPI *spi; - uint32 i = 0; - uint8 rc; +/** + * @brief Call a function on each SPI port + * @param fn Function to call. + */ +void spi_foreach(void (*fn)(spi_dev*)) { + fn(SPI1); + fn(SPI2); +#ifdef STM32_HIGH_DENSITY + fn(SPI3); +#endif +} - ASSERT(spi_num == 1 || spi_num == 2); - spi = (spi_num == 1) ? (SPI*)SPI1_BASE : (SPI*)SPI2_BASE; +/** + * @brief Enable a SPI peripheral + * @param dev Device to enable + */ +void spi_peripheral_enable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR1, SPI_CR1_SPE_BIT, 1); +} - if (!len) { - return 0; - } +/** + * @brief Disable a SPI peripheral + * @param dev Device to disable + */ +void spi_peripheral_disable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR1, SPI_CR1_SPE_BIT, 0); +} - while (i < len) { - while (!(spi->SR & SR_TXE)) - ; +/** + * @brief Enable DMA requests whenever the transmit buffer is empty + * @param dev SPI device on which to enable TX DMA requests + */ +void spi_tx_dma_enable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR2, SPI_CR2_TXDMAEN_BIT, 1); +} - spi->DR = buf[i]; +/** + * @brief Disable DMA requests whenever the transmit buffer is empty + * @param dev SPI device on which to disable TX DMA requests + */ +void spi_tx_dma_disable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR2, SPI_CR2_TXDMAEN_BIT, 0); +} - while (!(spi->SR & SR_RXNE)) - ; +/** + * @brief Enable DMA requests whenever the receive buffer is empty + * @param dev SPI device on which to enable RX DMA requests + */ +void spi_rx_dma_enable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR2, SPI_CR2_RXDMAEN_BIT, 1); +} - rc = spi->DR; - i++; - } - return rc; +/** + * @brief Disable DMA requests whenever the receive buffer is empty + * @param dev SPI device on which to disable RX DMA requests + */ +void spi_rx_dma_disable(spi_dev *dev) { + bb_peri_set_bit(&dev->regs->CR2, SPI_CR2_RXDMAEN_BIT, 0); } -static void spi_gpio_cfg(const spi_dev *dev) { - gpio_set_mode(dev->gpio_d, dev->sck_pin, GPIO_AF_OUTPUT_PP); - gpio_set_mode(dev->gpio_d, dev->miso_pin, GPIO_AF_OUTPUT_PP); - gpio_set_mode(dev->gpio_d, dev->mosi_pin, GPIO_AF_OUTPUT_PP); +/* + * SPI auxiliary routines + */ + +static void spi_reconfigure(spi_dev *dev, uint32 cr1_config) { + spi_irq_disable(dev, SPI_INTERRUPTS_ALL); + spi_peripheral_disable(dev); + dev->regs->CR1 = cr1_config; + spi_peripheral_enable(dev); } + +/* + * IRQ handlers (TODO) + */ diff --git a/libmaple/spi.h b/libmaple/spi.h index 5ebf52d..e2820dd 100644 --- a/libmaple/spi.h +++ b/libmaple/spi.h @@ -24,99 +24,440 @@ /** * @file spi.h - * @brief libmaple serial peripheral interface (SPI) prototypes and - * declarations + * @author Marti Bolivar + * @brief Serial Peripheral Interface (SPI) and Integrated + * Interchip Sound (I2S) peripheral support. + * + * I2S support is currently limited to register maps and bit definitions. */ #ifndef _SPI_H_ #define _SPI_H_ #include "libmaple_types.h" +#include "rcc.h" +#include "nvic.h" +#include "gpio.h" #include "util.h" #ifdef __cplusplus extern "C" { #endif -/* peripheral addresses */ -#define SPI1_BASE 0x40013000 -#define SPI2_BASE 0x40003800 -#define SPI3_BASE 0x40003C00 - -/* baud rate prescaler bits */ -#define CR1_BR 0x00000038 -#define CR1_BR_PRESCALE_2 0x00000000 -#define CR1_BR_PRESCALE_4 0x00000008 -#define CR1_BR_PRESCALE_8 0x00000010 -#define CR1_BR_PRESCALE_16 0x00000018 -#define CR1_BR_PRESCALE_32 0x00000020 -#define CR1_BR_PRESCALE_64 0x00000028 -#define CR1_BR_PRESCALE_128 0x00000030 -#define CR1_BR_PRESCALE_256 0x00000038 - -#define CR1_LSBFIRST BIT(7) // data frame format -#define CR1_MSTR BIT(2) // master selection -#define CR1_SSM BIT(9) // software slave management -#define CR1_SSI BIT(8) // internal slave select -#define CR1_SPE BIT(6) // peripheral enable - -/* Status register bits */ -#define SR_RXNE BIT(0) // rx buffer not empty -#define SR_TXE BIT(1) // transmit buffer empty -#define SR_BSY BIT(7) // busy flag - -typedef struct SPI { - __io uint16 CR1; - uint16 pad0; - __io uint8 CR2; - uint8 pad1[3]; - __io uint8 SR; - uint8 pad2[3]; - __io uint16 DR; - uint16 pad3; - __io uint16 CRCPR; - uint16 pad4; - __io uint16 RXCRCR; - uint16 pad5; - __io uint16 TXCRCR; - uint16 pad6; -} SPI; - -enum { - SPI_MSBFIRST = 0, - SPI_LSBFIRST = BIT(7), -}; - -enum { - SPI_PRESCALE_2 = (0x0 << 3), - SPI_PRESCALE_4 = (0x1 << 3), - SPI_PRESCALE_8 = (0x2 << 3), - SPI_PRESCALE_16 = (0x3 << 3), - SPI_PRESCALE_32 = (0x4 << 3), - SPI_PRESCALE_64 = (0x5 << 3), - SPI_PRESCALE_128 = (0x6 << 3), - SPI_PRESCALE_256 = (0x7 << 3) -}; - -void spi_init(uint32 spi_num, - uint32 prescale, - uint32 endian, - uint32 mode); -uint8 spi_tx_byte(uint32 spi_num, uint8 data); -uint8 spi_tx(uint32 spi_num, uint8 *buf, uint32 len); - -static inline uint8 spi_rx(uint32 spi_num) { - SPI *spi; - - ASSERT(spi_num == 1 || spi_num == 2); - spi = (spi_num == 1) ? (SPI*)SPI1_BASE : (SPI*)SPI2_BASE; - - return spi->DR; +/* + * Register maps + */ + +/** SPI register map type. */ +typedef struct spi_reg_map { + __io uint32 CR1; /**< Control register 1 */ + __io uint32 CR2; /**< Control register 2 */ + __io uint32 SR; /**< Status register */ + __io uint32 DR; /**< Data register */ + __io uint32 CRCPR; /**< CRC polynomial register */ + __io uint32 RXCRCR; /**< RX CRC register */ + __io uint32 TXCRCR; /**< TX CRC register */ + __io uint32 I2SCFGR; /**< I2S configuration register */ + __io uint32 I2SPR; /**< I2S prescaler register */ +} spi_reg_map; + +/** SPI1 register map base pointer */ +#define SPI1_BASE ((struct spi_reg_map*)0x40013000) +/** SPI2 register map base pointer */ +#define SPI2_BASE ((struct spi_reg_map*)0x40003800) +/** SPI3 register map base pointer */ +#define SPI3_BASE ((struct spi_reg_map*)0x40003C00) + +/* + * Register bit definitions + */ + +/* Control register 1 */ + +#define SPI_CR1_BIDIMODE_BIT 15 +#define SPI_CR1_BIDIOE_BIT 14 +#define SPI_CR1_CRCEN_BIT 13 +#define SPI_CR1_CRCNEXT_BIT 12 +#define SPI_CR1_DFF_BIT 11 +#define SPI_CR1_RXONLY_BIT 10 +#define SPI_CR1_SSM_BIT 9 +#define SPI_CR1_SSI_BIT 8 +#define SPI_CR1_LSBFIRST_BIT 7 +#define SPI_CR1_SPE_BIT 6 +#define SPI_CR1_MSTR_BIT 2 +#define SPI_CR1_CPOL_BIT 1 +#define SPI_CR1_CPHA_BIT 0 + +#define SPI_CR1_BIDIMODE BIT(SPI_CR1_BIDIMODE_BIT) +#define SPI_CR1_BIDIMODE_2_LINE (0x0 << SPI_CR1_BIDIMODE_BIT) +#define SPI_CR1_BIDIMODE_1_LINE (0x1 << SPI_CR1_BIDIMODE_BIT) +#define SPI_CR1_BIDIOE BIT(SPI_CR1_BIDIOE_BIT) +#define SPI_CR1_CRCEN BIT(SPI_CR1_CRCEN_BIT) +#define SPI_CR1_CRCNEXT BIT(SPI_CR1_CRCNEXT_BIT) +#define SPI_CR1_DFF BIT(SPI_CR1_DFF_BIT) +#define SPI_CR1_DFF_8_BIT (0x0 << SPI_CR1_DFF_BIT) +#define SPI_CR1_DFF_16_BIT (0x1 << SPI_CR1_DFF_BIT) +#define SPI_CR1_RXONLY BIT(SPI_CR1_RXONLY_BIT) +#define SPI_CR1_SSM BIT(SPI_CR1_SSM_BIT) +#define SPI_CR1_SSI BIT(SPI_CR1_SSI_BIT) +#define SPI_CR1_LSBFIRST BIT(SPI_CR1_LSBFIRST_BIT) +#define SPI_CR1_SPE BIT(SPI_CR1_SPE_BIT) +#define SPI_CR1_BR (0x7 << 3) +#define SPI_CR1_BR_PCLK_DIV_2 (0x0 << 3) +#define SPI_CR1_BR_PCLK_DIV_4 (0x1 << 3) +#define SPI_CR1_BR_PCLK_DIV_8 (0x2 << 3) +#define SPI_CR1_BR_PCLK_DIV_16 (0x3 << 3) +#define SPI_CR1_BR_PCLK_DIV_32 (0x4 << 3) +#define SPI_CR1_BR_PCLK_DIV_64 (0x5 << 3) +#define SPI_CR1_BR_PCLK_DIV_128 (0x6 << 3) +#define SPI_CR1_BR_PCLK_DIV_256 (0x7 << 3) +#define SPI_CR1_MSTR BIT(SPI_CR1_MSTR_BIT) +#define SPI_CR1_CPOL BIT(SPI_CR1_CPOL_BIT) +#define SPI_CR1_CPOL_LOW (0x0 << SPI_CR1_CPOL_BIT) +#define SPI_CR1_CPOL_HIGH (0x1 << SPI_CR1_CPOL_BIT) +#define SPI_CR1_CPHA BIT(SPI_CR1_CPHA_BIT) + +/* Control register 2 */ + +/* RM0008-ism: SPI CR2 has "TXDMAEN" and "RXDMAEN" bits, while the + * USARTs have CR3 "DMAR" and "DMAT" bits. */ + +#define SPI_CR2_TXEIE_BIT 7 +#define SPI_CR2_RXNEIE_BIT 6 +#define SPI_CR2_ERRIE_BIT 5 +#define SPI_CR2_SSOE_BIT 2 +#define SPI_CR2_TXDMAEN_BIT 1 +#define SPI_CR2_RXDMAEN_BIT 0 + +#define SPI_CR2_TXEIE BIT(SPI_CR2_TXEIE_BIT) +#define SPI_CR2_RXNEIE BIT(SPI_CR2_RXNEIE_BIT) +#define SPI_CR2_ERRIE BIT(SPI_CR2_ERRIE_BIT) +#define SPI_CR2_SSOE BIT(SPI_CR2_SSOE_BIT) +#define SPI_CR2_TXDMAEN BIT(SPI_CR2_TXDMAEN_BIT) +#define SPI_CR2_RXDMAEN BIT(SPI_CR2_RXDMAEN_BIT) + +/* Status register */ + +#define SPI_SR_BSY_BIT 7 +#define SPI_SR_OVR_BIT 6 +#define SPI_SR_MODF_BIT 5 +#define SPI_SR_CRCERR_BIT 4 +#define SPI_SR_UDR_BIT 3 +#define SPI_SR_CHSIDE_BIT 2 +#define SPI_SR_TXE_BIT 1 +#define SPI_SR_RXNE_BIT 0 + +#define SPI_SR_BSY BIT(SPI_SR_BSY_BIT) +#define SPI_SR_OVR BIT(SPI_SR_OVR_BIT) +#define SPI_SR_MODF BIT(SPI_SR_MODF_BIT) +#define SPI_SR_CRCERR BIT(SPI_SR_CRCERR_BIT) +#define SPI_SR_UDR BIT(SPI_SR_UDR_BIT) +#define SPI_SR_CHSIDE BIT(SPI_SR_CHSIDE_BIT) +#define SPI_SR_CHSIDE_LEFT (0x0 << SPI_SR_CHSIDE_BIT) +#define SPI_SR_CHSIDE_RIGHT (0x1 << SPI_SR_CHSIDE_BIT) +#define SPI_SR_TXE BIT(SPI_SR_TXE_BIT) +#define SPI_SR_RXNE BIT(SPI_SR_RXNE_BIT) + +/* I2S configuration register */ + +/* RM0008-ism: CR1 has "CPOL", I2SCFGR has "CKPOL". */ + +#define SPI_I2SCFGR_I2SMOD_BIT 11 +#define SPI_I2SCFGR_I2SE_BIT 10 +#define SPI_I2SCFGR_PCMSYNC_BIT 7 +#define SPI_I2SCFGR_CKPOL_BIT 3 +#define SPI_I2SCFGR_CHLEN_BIT 0 + +#define SPI_I2SCFGR_I2SMOD BIT(SPI_I2SCFGR_I2SMOD_BIT) +#define SPI_I2SCFGR_I2SMOD_SPI (0x0 << SPI_I2SCFGR_I2SMOD_BIT) +#define SPI_I2SCFGR_I2SMOD_I2S (0x1 << SPI_I2SCFGR_I2SMOD_BIT) +#define SPI_I2SCFGR_I2SE BIT(SPI_I2SCFGR_I2SE_BIT) +#define SPI_I2SCFGR_I2SCFG (0x3 << 8) +#define SPI_I2SCFGR_I2SCFG_SLAVE_TX (0x0 << 8) +#define SPI_I2SCFGR_I2SCFG_SLAVE_RX (0x1 << 8) +#define SPI_I2SCFGR_I2SCFG_MASTER_TX (0x2 << 8) +#define SPI_I2SCFGR_I2SCFG_MASTER_RX (0x3 << 8) +#define SPI_I2SCFGR_PCMSYNC BIT(SPI_I2SCFGR_PCMSYNC_BIT) +#define SPI_I2SCFGR_PCMSYNC_SHORT (0x0 << SPI_I2SCFGR_PCMSYNC_BIT) +#define SPI_I2SCFGR_PCMSYNC_LONG (0x1 << SPI_I2SCFGR_PCMSYNC_BIT) +#define SPI_I2SCFGR_I2SSTD (0x3 << 4) +#define SPI_I2SCFGR_I2SSTD_PHILLIPS (0x0 << 4) +#define SPI_I2SCFGR_I2SSTD_MSB (0x1 << 4) +#define SPI_I2SCFGR_I2SSTD_LSB (0x2 << 4) +#define SPI_I2SCFGR_I2SSTD_PCM (0x3 << 4) +#define SPI_I2SCFGR_CKPOL BIT(SPI_I2SCFGR_CKPOL_BIT) +#define SPI_I2SCFGR_CKPOL_LOW (0x0 << SPI_I2SCFGR_CKPOL_BIT) +#define SPI_I2SCFGR_CKPOL_HIGH (0x1 << SPI_I2SCFGR_CKPOL_BIT) +#define SPI_I2SCFGR_DATLEN (0x3 << 1) +#define SPI_I2SCFGR_DATLEN_16_BIT (0x0 << 1) +#define SPI_I2SCFGR_DATLEN_24_BIT (0x1 << 1) +#define SPI_I2SCFGR_DATLEN_32_BIT (0x2 << 1) +#define SPI_I2SCFGR_CHLEN BIT(SPI_I2SCFGR_CHLEN_BIT) +#define SPI_I2SCFGR_CHLEN_16_BIT (0x0 << SPI_I2SCFGR_CHLEN_BIT) +#define SPI_I2SCFGR_CHLEN_32_BIT (0x1 << SPI_I2SCFGR_CHLEN_BIT) + +/* + * Devices + */ + +/** SPI device type */ +typedef struct spi_dev { + spi_reg_map *regs; + rcc_clk_id clk_id; + nvic_irq_num irq_num; +} spi_dev; + +/** SPI device 1 */ +extern spi_dev *SPI1; +/** SPI device 2 */ +extern spi_dev *SPI2; +#ifdef STM32_HIGH_DENSITY +/** SPI device 3 */ +extern spi_dev *SPI3; +#endif + +/* + * SPI Convenience functions + */ + +void spi_init(spi_dev *dev); + +void spi_master_gpio_cfg(gpio_dev *nss_dev, + gpio_dev *comm_dev, + uint8 nss_bit, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit); + +void spi_slave_gpio_cfg(gpio_dev *nss_dev, + gpio_dev *comm_dev, + uint8 nss_bit, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit); + +/** + * @brief SPI mode configuration. + * + * Determines a combination of clock polarity (CPOL), which determines + * idle state of the clock line, and clock phase (CPHA), which + * determines which clock edge triggers data capture. + */ +typedef enum { + SPI_MODE_0, /**< Clock line idles low (0), data capture on first + clock transition. */ + SPI_MODE_1, /**< Clock line idles low (0), data capture on second + clock transition */ + SPI_MODE_2, /**< Clock line idles high (1), data capture on first + clock transition. */ + SPI_MODE_3 /**< Clock line idles high (1), data capture on + second clock transition. */ +} spi_mode; + +/** + * @brief SPI baud rate configuration, as a divisor of f_PCLK, the + * PCLK clock frequency. + */ +typedef enum { + SPI_BAUD_PCLK_DIV_2 = SPI_CR1_BR_PCLK_DIV_2, /**< f_PCLK/2 */ + SPI_BAUD_PCLK_DIV_4 = SPI_CR1_BR_PCLK_DIV_4, /**< f_PCLK/4 */ + SPI_BAUD_PCLK_DIV_8 = SPI_CR1_BR_PCLK_DIV_8, /**< f_PCLK/8 */ + SPI_BAUD_PCLK_DIV_16 = SPI_CR1_BR_PCLK_DIV_16, /**< f_PCLK/16 */ + SPI_BAUD_PCLK_DIV_32 = SPI_CR1_BR_PCLK_DIV_32, /**< f_PCLK/32 */ + SPI_BAUD_PCLK_DIV_64 = SPI_CR1_BR_PCLK_DIV_64, /**< f_PCLK/64 */ + SPI_BAUD_PCLK_DIV_128 = SPI_CR1_BR_PCLK_DIV_128, /**< f_PCLK/128 */ + SPI_BAUD_PCLK_DIV_256 = SPI_CR1_BR_PCLK_DIV_256, /**< f_PCLK/256 */ +} spi_baud_rate; + +/** + * @brief SPI initialization flags. + * @see spi_master_enable() + * @see spi_slave_enable() + */ +typedef enum { + SPI_BIDIMODE = SPI_CR1_BIDIMODE, /**< Bidirectional mode enable */ + SPI_BIDIOE = SPI_CR1_BIDIOE, /**< Output enable in bidirectional + mode */ + SPI_CRCEN = SPI_CR1_CRCEN, /**< Cyclic redundancy check (CRC) + enable */ + SPI_DFF_8_BIT = SPI_CR1_DFF_8_BIT, /**< 8-bit data frame format (this is + the default) */ + SPI_DFF_16_BIT = SPI_CR1_DFF_16_BIT, /**< 16-bit data frame format */ + SPI_RX_ONLY = SPI_CR1_RXONLY, /**< Receive only */ + SPI_SW_SLAVE = SPI_CR1_SSM, /**< Software slave management */ + SPI_SOFT_SS = SPI_CR1_SSI, /**< Software (internal) slave + select. This flag only has an + effect when used in combination + with SPI_SW_SLAVE. */ + SPI_FRAME_LSB = SPI_CR1_LSBFIRST, /**< LSB-first (little-endian) frame + format */ + SPI_FRAME_MSB = 0, /**< MSB-first (big-endian) frame + format (this is the default) */ +} spi_cfg_flag; + +void spi_master_enable(spi_dev *dev, + spi_baud_rate baud, + spi_mode mode, + uint32 flags); + +void spi_slave_enable(spi_dev *dev, + spi_mode mode, + uint32 flags); + +uint32 spi_tx(spi_dev *dev, const void *buf, uint32 len); + +void spi_foreach(void (*fn)(spi_dev (*dev))); + +void spi_peripheral_enable(spi_dev *dev); +void spi_peripheral_disable(spi_dev *dev); + +void spi_tx_dma_enable(spi_dev *dev); +void spi_tx_dma_disable(spi_dev *dev); + +void spi_rx_dma_enable(spi_dev *dev); +void spi_rx_dma_disable(spi_dev *dev); + +/** + * @brief Determine if a SPI peripheral is enabled. + * @parm dev SPI device + * @return True, if and only if dev's peripheral is enabled. + */ +static inline uint8 spi_is_enabled(spi_dev *dev) { + return dev->regs->CR1 & SPI_CR1_SPE_BIT; +} + +/** + * @brief Disable all SPI peripherals + */ +static inline void spi_peripheral_disable_all(void) { + spi_foreach(spi_peripheral_disable); +} + +/** Available SPI interrupts */ +typedef enum { + SPI_TXE_INTERRUPT = SPI_CR2_TXEIE, /**< TX buffer empty interrupt */ + SPI_RXNE_INTERRUPT = SPI_CR2_RXNEIE, /**< RX buffer not empty interrupt */ + SPI_ERR_INTERRUPT = SPI_CR2_ERRIE /**< + * Error interrupt (CRC, overrun, + * and mode fault errors for SPI; + * underrun, overrun errors for I2S) + */ +} spi_interrupt; + +/** + * @brief Mask for all spi_interrupt values + * @see spi_interrupt + */ +#define SPI_INTERRUPTS_ALL (SPI_TXE_INTERRUPT | \ + SPI_RXNE_INTERRUPT | \ + SPI_ERR_INTERRUPT) + +/** + * @brief Enable SPI interrupt requests + * @param dev SPI device + * @param interrupt_flags Bitwise OR of spi_interrupt values to enable + * @see spi_interrupt + */ +static inline void spi_irq_enable(spi_dev *dev, uint32 interrupt_flags) { + dev->regs->CR2 |= interrupt_flags; + nvic_irq_enable(dev->irq_num); +} + +/** + * @brief Disable SPI interrupt requests + * @param dev SPI device + * @param interrupt_flags Bitwise OR of spi_interrupt values to disable + * @see spi_interrupt + */ +static inline void spi_irq_disable(spi_dev *dev, uint32 interrupt_flags) { + dev->regs->CR2 &= ~interrupt_flags; +} + +/** + * @brief Get the data frame format flags with which a SPI port is + * configured. + * @param dev SPI device whose data frame format to get. + * @return SPI_DFF_8_BIT, if dev has an 8-bit data frame format. + * Otherwise, SPI_DFF_16_BIT. + */ +static inline spi_cfg_flag spi_dff(spi_dev *dev) { + return ((dev->regs->CR1 & SPI_CR1_DFF) == SPI_CR1_DFF_8_BIT ? + SPI_DFF_8_BIT : + SPI_DFF_16_BIT); +} + +/** + * @brief Determine whether the device's peripheral receive (RX) + * register is empty. + * @param dev SPI device + * @return true, iff dev's RX register is empty. + */ +static inline uint8 spi_is_rx_nonempty(spi_dev *dev) { + return dev->regs->SR & SPI_SR_RXNE; +} + +/** + * @brief Retrieve the contents of the device's peripheral receive + * (RX) register. + * + * You may only call this function when the RX register is nonempty. + * Calling this function clears the contents of the RX register. + * + * @param dev SPI device + * @return Contents of dev's peripheral RX register + * @see spi_is_rx_reg_nonempty() + */ +static inline uint16 spi_rx_reg(spi_dev *dev) { + return (uint16)dev->regs->DR; +} + +/** + * @brief Determine whether the device's peripheral transmit (TX) + * register is empty. + * @param dev SPI device + * @return true, iff dev's TX register is empty. + */ +static inline uint8 spi_is_tx_empty(spi_dev *dev) { + return dev->regs->SR & SPI_SR_TXE; +} + +/** + * @brief Load a value into the device's peripheral transmit (TX) register. + * + * You may only call this function when the TX register is empty. + * Calling this function loads val into the peripheral's TX register. + * If the device is properly configured, this will initiate a + * transmission, the completion of which will cause the TX register to + * be empty again. + * + * @param dev SPI device + * @param val Value to load into the TX register. If the SPI data + * frame format is 8 bit, the value must be right-aligned. + * @see spi_is_tx_reg_empty() + * @see spi_init() + * @see spi_master_enable() + * @see spi_slave_enable() + */ +static inline void spi_tx_reg(spi_dev *dev, uint16 val) { + dev->regs->DR = val; +} + +/** + * @brief Determine whether the device's peripheral busy (SPI_SR_BSY) + * flag is set. + * @param dev SPI device + * @return true, iff dev's BSY flag is set. + */ +static inline uint8 spi_is_busy(spi_dev *dev) { + return dev->regs->SR & SPI_SR_BSY; } +/* + * I2S convenience functions (TODO) + */ + #ifdef __cplusplus } #endif #endif - diff --git a/wirish/boards/maple.h b/wirish/boards/maple.h index 4a4465c..4b55f7a 100644 --- a/wirish/boards/maple.h +++ b/wirish/boards/maple.h @@ -52,6 +52,19 @@ #define BOARD_USART3_TX_PIN 29 #define BOARD_USART3_RX_PIN 30 +/* Number of SPI ports */ +#define BOARD_NR_SPI 2 + +/* Default SPI pin numbers (not considering AFIO remap) */ +#define BOARD_SPI1_NSS_PIN 10 +#define BOARD_SPI1_MOSI_PIN 11 +#define BOARD_SPI1_MISO_PIN 12 +#define BOARD_SPI1_SCK_PIN 13 +#define BOARD_SPI2_NSS_PIN 31 +#define BOARD_SPI2_MOSI_PIN 34 +#define BOARD_SPI2_MISO_PIN 33 +#define BOARD_SPI2_SCK_PIN 32 + /* Total number of GPIO pins that are broken out to headers and * intended for general use. */ #define BOARD_NR_GPIO_PINS 44 diff --git a/wirish/boards/maple_RET6.h b/wirish/boards/maple_RET6.h index 97e609d..4195857 100644 --- a/wirish/boards/maple_RET6.h +++ b/wirish/boards/maple_RET6.h @@ -55,6 +55,16 @@ #define BOARD_USART3_TX_PIN 29 #define BOARD_USART3_RX_PIN 30 +#define BOARD_NR_SPI 2 +#define BOARD_SPI1_NSS_PIN 10 +#define BOARD_SPI1_MOSI_PIN 11 +#define BOARD_SPI1_MISO_PIN 12 +#define BOARD_SPI1_SCK_PIN 13 +#define BOARD_SPI2_NSS_PIN 31 +#define BOARD_SPI2_MOSI_PIN 34 +#define BOARD_SPI2_MISO_PIN 33 +#define BOARD_SPI2_SCK_PIN 32 + #define BOARD_NR_GPIO_PINS 44 #define BOARD_NR_PWM_PINS 16 #define BOARD_NR_ADC_PINS 15 diff --git a/wirish/boards/maple_mini.h b/wirish/boards/maple_mini.h index 3df1da8..fde7f98 100644 --- a/wirish/boards/maple_mini.h +++ b/wirish/boards/maple_mini.h @@ -54,6 +54,16 @@ #define BOARD_USART3_TX_PIN 1 #define BOARD_USART3_RX_PIN 0 +#define BOARD_NR_SPI 2 +#define BOARD_SPI1_NSS_PIN 7 +#define BOARD_SPI1_MOSI_PIN 4 +#define BOARD_SPI1_MISO_PIN 5 +#define BOARD_SPI1_SCK_PIN 6 +#define BOARD_SPI2_NSS_PIN 31 +#define BOARD_SPI2_MOSI_PIN 28 +#define BOARD_SPI2_MISO_PIN 29 +#define BOARD_SPI2_SCK_PIN 30 + #define BOARD_NR_GPIO_PINS 34 #define BOARD_NR_PWM_PINS 12 #define BOARD_NR_ADC_PINS 10 diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index ab8b282..c1f8d5c 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -171,7 +171,7 @@ extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = { 54, 55 }; -/* FIXME! see comment by BOARD_NR_USED_PINS in maple_native.h */ +/* FIXME [0.0.10] see comment by BOARD_NR_USED_PINS in maple_native.h */ extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN, BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h index 13df153..2cbd406 100644 --- a/wirish/boards/maple_native.h +++ b/wirish/boards/maple_native.h @@ -58,12 +58,27 @@ #define BOARD_UART5_TX_PIN 21 #define BOARD_UART5_RX_PIN 29 +#define BOARD_NR_SPI 3 +#define BOARD_SPI1_NSS_PIN 52 +#define BOARD_SPI1_MOSI_PIN 55 +#define BOARD_SPI1_MISO_PIN 54 +#define BOARD_SPI1_SCK_PIN 53 +#define BOARD_SPI2_NSS_PIN 2 +#define BOARD_SPI2_MOSI_PIN 5 +#define BOARD_SPI2_MISO_PIN 4 +#define BOARD_SPI2_SCK_PIN 3 +#define BOARD_SPI3_NSS_PIN 103 +#define BOARD_SPI3_MOSI_PIN 37 +#define BOARD_SPI3_MISO_PIN 105 +#define BOARD_SPI3_SCK_PIN 104 + #define BOARD_NR_GPIO_PINS 106 #define BOARD_NR_PWM_PINS 18 #define BOARD_NR_ADC_PINS 21 -/* FIXME! this isn't true at all; almost all of the triple header pins - * are used by the FSMC by default. Fix this (and the corresponding - * boardUsedPins definition in maple_native.cpp) by QA time. */ +/* FIXME [0.0.10] this isn't true at all; almost all of the triple + * header pins are used by the FSMC by default. Fix this (and the + * corresponding boardUsedPins definition in maple_native.cpp) by QA + * time. */ #define BOARD_NR_USED_PINS 7 #define BOARD_JTMS_SWDIO_PIN 101 diff --git a/wirish/comm/HardwareSPI.cpp b/wirish/comm/HardwareSPI.cpp index aea7734..1b36d21 100644 --- a/wirish/comm/HardwareSPI.cpp +++ b/wirish/comm/HardwareSPI.cpp @@ -23,120 +23,283 @@ *****************************************************************************/ /** - * @brief HardwareSPI "wiring-like" api for SPI + * @author Marti Bolivar + * @brief Wirish SPI implementation. */ -/* NOTES: - * - * Speeds: - * ----------------------------------- - * Interface num: SPI1 SPI2 - * Bus APB2 APB1 - * ----------------------------------- - * Prescaler Frequencies - * ----------------------------------- - * 2: N/A 18 000 000 - * 4: 18 000 000 9 000 000 - * 8: 9 000 000 4 500 000 - * 16: 4 500 000 2 250 000 - * 32: 2 250 000 1 125 000 - * 64: 1 125 000 562 500 - * 128: 562 500 281 250 - * 256: 281 250 140 625 - * - * TODO: Do the complementary PWM outputs mess up SPI2? - * */ +#include "HardwareSPI.h" -#include "spi.h" #include "timer.h" +#include "util.h" #include "wirish.h" -#include "HardwareSPI.h" +#include "boards.h" -static const uint32 prescaleFactors[MAX_SPI_FREQS] = { - SPI_PRESCALE_2, // SPI_18MHZ - SPI_PRESCALE_4, // SPI_9MHZ - SPI_PRESCALE_8, // SPI_4_5MHZ - SPI_PRESCALE_16, // SPI_2_25MHZ - SPI_PRESCALE_32, // SPI_1_125MHZ - SPI_PRESCALE_64, // SPI_562_500KHZ - SPI_PRESCALE_128, // SPI_281_250KHZ - SPI_PRESCALE_256, // SPI_140_625KHZ -}; +static void enable_device(spi_dev *dev, + bool as_master, + SPIFrequency frequency, + spi_cfg_flag endianness, + spi_mode mode); -/** - * @brief Initialize a SPI peripheral - * @param freq frequency to run at, must one of the following values: - * - SPI_18MHZ - * - SPI_9MHZ - * - SPI_4_5MHZ - * - SPI_2_25MHZ - * - SPI_1_125MHZ - * - SPI_562_500KHZ - * - SPI_281_250KHZ - * - SPI_140_625KHZ - * @param endianness endianness of the data frame, must be either LSBFIRST - * or MSBFIRST - * @param mode SPI standard CPOL and CPHA levels +/* + * Constructor, public methods */ -void HardwareSPI::begin(SPIFrequency freq, uint32 endianness, uint32 mode) { - uint32 spi_num = this->spi_num; - uint32 prescale; - - if ((freq >= MAX_SPI_FREQS) || - !((endianness == LSBFIRST) || - (endianness == MSBFIRST)) || - (mode >= 4)) { + +HardwareSPI::HardwareSPI(uint32 spi_num) { + switch (spi_num) { + case 1: + this->spi_d = SPI1; + break; + case 2: + this->spi_d = SPI2; + break; +#ifdef STM32_HIGH_DENSITY + case 3: + this->spi_d = SPI3; + break; +#endif + default: + ASSERT(0); + } +} + +void HardwareSPI::begin(SPIFrequency frequency, uint32 bitOrder, uint32 mode) { + if (mode >= 4) { + ASSERT(0); return; } + spi_cfg_flag end = bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB; + spi_mode m = (spi_mode)mode; + enable_device(this->spi_d, true, frequency, end, m); +} - if (spi_num == 1) { - /* SPI1 is too fast for 140625 */ - if (freq == SPI_140_625KHZ) { - return; - } +void HardwareSPI::begin(void) { + this->begin(SPI_1_125MHZ, MSBFIRST, 0); +} - /* Turn off PWM on shared pins */ - timer_set_mode(TIMER3, 2, TIMER_DISABLED); - timer_set_mode(TIMER3, 1, TIMER_DISABLED); +void HardwareSPI::beginSlave(uint32 bitOrder, uint32 mode) { + if (mode >= 4) { + ASSERT(0); + return; } + spi_cfg_flag end = bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB; + spi_mode m = (spi_mode)mode; + enable_device(this->spi_d, false, (SPIFrequency)0, end, m); +} - endianness = (endianness == LSBFIRST) ? SPI_LSBFIRST : SPI_MSBFIRST; - prescale = (spi_num == 1) ? - prescaleFactors[freq + 1] : - prescaleFactors[freq]; +void HardwareSPI::beginSlave(void) { + this->beginSlave(MSBFIRST, 0); +} - spi_init(spi_num, prescale, endianness, mode); +void HardwareSPI::end(void) { + if (!spi_is_enabled(this->spi_d)) { + return; + } + + // Follows RM0008's sequence for disabling a SPI in master/slave + // full duplex mode. + while (spi_is_rx_nonempty(this->spi_d)) { + // FIXME [0.1.0] remove this once you have an interrupt based driver + volatile uint16 rx __attribute__((unused)) = spi_rx_reg(this->spi_d); + } + while (!spi_is_tx_empty(this->spi_d)) + ; + while (spi_is_busy(this->spi_d)) + ; + spi_peripheral_disable(this->spi_d); } -/** - * @brief Initialize a SPI peripheral with a default speed of 1.125 - * MHZ, MSBFIRST, mode 0 - */ -void HardwareSPI::begin(void) { - begin(SPI_1_125MHZ, MSBFIRST, 0); +uint8 HardwareSPI::read(void) { + uint8 buf[1]; + this->read(buf, 1); + return buf[0]; } -/** - * @brief send a byte out the spi peripheral - * @param data byte to send +void HardwareSPI::read(uint8 *buf, uint32 len) { + uint32 rxed = 0; + while (rxed < len) { + while (!spi_is_rx_nonempty(this->spi_d)) + ; + buf[rxed++] = (uint8)spi_rx_reg(this->spi_d); + } +} + +void HardwareSPI::write(uint8 byte) { + uint8 buf[] = {byte}; + this->write(buf, 1); +} + +void HardwareSPI::write(uint8 *data, uint32 length) { + uint32 txed = 0; + while (txed < length) { + txed += spi_tx(this->spi_d, data + txed, length - txed); + } +} + +uint8 HardwareSPI::transfer(uint8 byte) { + this->write(byte); + return this->read(); +} + +/* + * Deprecated functions */ + uint8 HardwareSPI::send(uint8 data) { - return spi_tx_byte(this->spi_num, data); + uint8 buf[] = {data}; + return this->send(buf, 1); } uint8 HardwareSPI::send(uint8 *buf, uint32 len) { - return spi_tx(this->spi_num, buf, len); + if (len == 0) { + ASSERT(0); + return 0; + } + uint32 txed = 0; + uint8 ret = 0; // shut up, GCC + while (txed < len) { + this->write(buf[txed++]); + ret = this->read(); + } + return ret; } -/** - * @brief read a byte from the spi peripheral - * @return byte in the buffer - */ uint8 HardwareSPI::recv(void) { - return spi_rx(this->spi_num); + return this->read(); } -HardwareSPI::HardwareSPI(uint32 spi_num) { - this->spi_num = spi_num; +/* + * Auxiliary functions + */ + +static void configure_gpios(spi_dev *dev, bool as_master); +static spi_baud_rate determine_baud_rate(spi_dev *dev, SPIFrequency freq); + +/* Enables the device in master or slave full duplex mode. If you + * change this code, you must ensure that appropriate changes are made + * to HardwareSPI::end(). */ +static void enable_device(spi_dev *dev, + bool as_master, + SPIFrequency freq, + spi_cfg_flag endianness, + spi_mode mode) { + if (freq >= MAX_SPI_FREQS) { + ASSERT(0); + return; + } + + spi_baud_rate baud = determine_baud_rate(dev, freq); + uint32 cfg_flags = (endianness | SPI_DFF_8_BIT | SPI_SW_SLAVE | + (as_master ? SPI_SOFT_SS : 0)); + + spi_init(dev); + configure_gpios(dev, as_master); + if (as_master) { + spi_master_enable(dev, baud, mode, cfg_flags); + } else { + spi_slave_enable(dev, mode, cfg_flags); + } +} + +static void disable_pwm(const stm32_pin_info *i) { + if (i->timer_device) { + timer_set_mode(i->timer_device, i->timer_channel, TIMER_DISABLED); + } +} + +typedef struct spi_pins { + uint8 nss; + uint8 sck; + uint8 miso; + uint8 mosi; +} spi_pins; + +static void configure_gpios(spi_dev *dev, bool as_master) { + const spi_pins spi_pin_config[] = { + {BOARD_SPI1_NSS_PIN, + BOARD_SPI1_SCK_PIN, + BOARD_SPI1_MISO_PIN, + BOARD_SPI1_MOSI_PIN}, + {BOARD_SPI2_NSS_PIN, + BOARD_SPI2_SCK_PIN, + BOARD_SPI2_MISO_PIN, + BOARD_SPI2_MOSI_PIN}, +#ifdef STM32_HIGH_DENSITY + {BOARD_SPI3_NSS_PIN, + BOARD_SPI3_SCK_PIN, + BOARD_SPI3_MISO_PIN, + BOARD_SPI3_MOSI_PIN}, +#endif + }; + + const spi_pins *pins; + + switch (dev->clk_id) { + case RCC_SPI1: + pins = &spi_pin_config[0]; + break; + case RCC_SPI2: + pins = &spi_pin_config[1]; + break; +#ifdef STM32_HIGH_DENSITY + case RCC_SPI3: + pins = &spi_pin_config[2]; + break; +#endif + default: + ASSERT(0); + return; + } + + const stm32_pin_info *nssi = &PIN_MAP[pins->nss]; + const stm32_pin_info *scki = &PIN_MAP[pins->sck]; + const stm32_pin_info *misoi = &PIN_MAP[pins->miso]; + const stm32_pin_info *mosii = &PIN_MAP[pins->mosi]; + + disable_pwm(nssi); + disable_pwm(scki); + disable_pwm(misoi); + disable_pwm(mosii); + + if (as_master) { + spi_master_gpio_cfg(nssi->gpio_device, + scki->gpio_device, + nssi->gpio_bit, + scki->gpio_bit, + misoi->gpio_bit, + mosii->gpio_bit); + } else { + spi_slave_gpio_cfg(nssi->gpio_device, + scki->gpio_device, + nssi->gpio_bit, + scki->gpio_bit, + misoi->gpio_bit, + mosii->gpio_bit); + } +} + +static const spi_baud_rate baud_rates[MAX_SPI_FREQS] __FLASH__ = { + SPI_BAUD_PCLK_DIV_2, + SPI_BAUD_PCLK_DIV_4, + SPI_BAUD_PCLK_DIV_8, + SPI_BAUD_PCLK_DIV_16, + SPI_BAUD_PCLK_DIV_32, + SPI_BAUD_PCLK_DIV_64, + SPI_BAUD_PCLK_DIV_128, + SPI_BAUD_PCLK_DIV_256, +}; + +/* + * Note: This assumes you're on a LeafLabs-style board + * (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz). + */ +static spi_baud_rate determine_baud_rate(spi_dev *dev, SPIFrequency freq) { + if (rcc_dev_clk(dev->clk_id) == RCC_APB2 && freq == SPI_140_625KHZ) { + /* APB2 peripherals are too fast for 140.625 KHz */ + ASSERT(0); + return (spi_baud_rate)~0; + } + return (rcc_dev_clk(dev->clk_id) == RCC_APB2 ? + baud_rates[freq + 1] : + baud_rates[freq]); } diff --git a/wirish/comm/HardwareSPI.h b/wirish/comm/HardwareSPI.h index 7241d0b..1b2a966 100644 --- a/wirish/comm/HardwareSPI.h +++ b/wirish/comm/HardwareSPI.h @@ -3,60 +3,188 @@ * * Copyright (c) 2010 Perry Hung. * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. *****************************************************************************/ /** - * @brief HardwareSPI definitions + * @file HardwareSPI.h + * @brief High-level SPI interface + * + * This is a "bare essentials" polling driver for now. */ +/* TODO [0.1.0] Remove deprecated methods. */ + +#include "libmaple_types.h" +#include "spi.h" + +#include "boards.h" + #ifndef _HARDWARESPI_H_ #define _HARDWARESPI_H_ /** - * Defines the possible SPI communication speeds. + * @brief Defines the possible SPI communication speeds. */ typedef enum SPIFrequency { SPI_18MHZ = 0, /**< 18 MHz */ SPI_9MHZ = 1, /**< 9 MHz */ SPI_4_5MHZ = 2, /**< 4.5 MHz */ - SPI_2_25MHZ = 3, /**< 2.25 MHZ */ + SPI_2_25MHZ = 3, /**< 2.25 MHz */ SPI_1_125MHZ = 4, /**< 1.125 MHz */ SPI_562_500KHZ = 5, /**< 562.500 KHz */ SPI_281_250KHZ = 6, /**< 281.250 KHz */ SPI_140_625KHZ = 7, /**< 140.625 KHz */ - MAX_SPI_FREQS = 8, /**< The number of SPI frequencies. */ } SPIFrequency; -/* Documented by hand in docs/source/lang/api/hardwarespi.rst; if you - make any changes, make sure to update this document. */ +#define MAX_SPI_FREQS 8 + +#if CYCLES_PER_MICROSECOND != 72 +/* TODO [0.2.0?] something smarter than this */ +#warn "Unexpected clock speed; SPI frequency calculation will be incorrect" +#endif + +/** + * @brief Wirish SPI interface. + * + * This implementation uses software slave management, so the caller + * is responsible for controlling the slave select line. + */ class HardwareSPI { - private: - uint32 spi_num; +public: + /** + * @param spiPortNumber Number of the SPI port to manage. + */ + HardwareSPI(uint32 spiPortNumber); + + /** + * @brief Turn on a SPI port and set its GPIO pin modes for use as master. + * + * SPI port is enabled in full duplex mode, with software slave management. + * + * @param frequency Communication frequency + * @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST (big-endian) + * @param mode SPI mode to use, one of SPI_MODE_0, SPI_MODE_1, + * SPI_MODE_2, and SPI_MODE_3. + */ + void begin(SPIFrequency frequency, uint32 bitOrder, uint32 mode); - public: - HardwareSPI(uint32 spi_num); + /** + * @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0). + */ void begin(void); - void begin(SPIFrequency freq, uint32 endianness, uint32 mode); + + /** + * @brief Turn on a SPI port and set its GPIO pin modes for use as a slave. + * + * SPI port is enabled in full duplex mode, with software slave management. + * + * @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST(big-endian) + * @param mode SPI mode to use + */ + void beginSlave(uint32 bitOrder, uint32 mode); + + /** + * @brief Equivalent to beginSlave(MSBFIRST, 0). + */ + void beginSlave(void); + + /** + * @brief Disables the SPI port, but leaves its GPIO pin modes unchanged. + */ + void end(void); + + /** + * @brief Return the next unread byte. + * + * If there is no unread byte waiting, this function will block + * until one is received. + */ + uint8 read(void); + + /** + * @brief Read length bytes, storing them into buffer. + * @param buffer Buffer to store received bytes into. + * @param length Number of bytes to store in buffer. This + * function will block until the desired number of + * bytes have been read. + */ + void read(uint8 *buffer, uint32 length); + + /** + * @brief Transmit a byte. + * @param data Byte to transmit. + */ + void write(uint8 data); + + /** + * @brief Transmit multiple bytes. + * @param buffer Bytes to transmit. + * @param length Number of bytes in buffer to transmit. + */ + void write(uint8 *buffer, uint32 length); + + /** + * @brief Transmit a byte, then return the next unread byte. + * + * This function transmits before receiving. + * + * @param data Byte to transmit. + * @return Next unread byte. + */ + uint8 transfer(uint8 data); + + /* -- The following methods are deprecated --------------------------- */ + + /** + * @brief Deprecated. + * + * Use HardwareSPI::transfer() instead. + * + * @see HardwareSPI::transfer() + */ uint8 send(uint8 data); + + /** + * @brief Deprecated. + * + * Use HardwareSPI::write() in combination with + * HardwareSPI::read() (or HardwareSPI::transfer()) instead. + * + * @see HardwareSPI::write() + * @see HardwareSPI::read() + * @see HardwareSPI::transfer() + */ uint8 send(uint8 *data, uint32 length); + + /** + * @brief Deprecated. + * + * Use HardwareSPI::read() instead. + * + * @see HardwareSPI::read() + */ uint8 recv(void); +private: + spi_dev *spi_d; }; #endif -- cgit v1.2.3 From 7caa5711c3f2d03870cba71d175a057e573aff8d Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Fri, 29 Apr 2011 12:28:30 -0400 Subject: Native and FSMC cleanups. Got rid of native_sram.h (and native_sram.cpp), and pushed their functionality into maple_native.cpp. Fixed includes in maple_native.h. Fixed includes in fsmc.h. --- libmaple/fsmc.c | 4 +--- libmaple/fsmc.h | 14 +++++++------ wirish/boards/maple_native.cpp | 23 +++++++++++++++++++-- wirish/boards/maple_native.h | 5 ----- wirish/native_sram.cpp | 45 ------------------------------------------ wirish/native_sram.h | 43 ---------------------------------------- wirish/rules.mk | 3 +-- 7 files changed, 31 insertions(+), 106 deletions(-) delete mode 100644 wirish/native_sram.cpp delete mode 100644 wirish/native_sram.h (limited to 'wirish') diff --git a/libmaple/fsmc.c b/libmaple/fsmc.c index 70d7e0d..356e1e5 100644 --- a/libmaple/fsmc.c +++ b/libmaple/fsmc.c @@ -26,10 +26,8 @@ * @brief */ -#include "libmaple.h" -#include "rcc.h" -#include "gpio.h" #include "fsmc.h" +#include "gpio.h" #ifdef STM32_HIGH_DENSITY diff --git a/libmaple/fsmc.h b/libmaple/fsmc.h index fccaf0b..8b6cac5 100644 --- a/libmaple/fsmc.h +++ b/libmaple/fsmc.h @@ -26,6 +26,8 @@ * See ../notes/fsmc.txt for more info */ +#include "libmaple_types.h" + /** * @file fsmc.h */ @@ -83,10 +85,10 @@ typedef struct fsmc_reg_map { __io uint32 BWTR4; /**< SRAM/NOR-Flash write timing register 4 */ } __attribute__((packed)) fsmc_reg_map; -#define __FSMC_B 0xA0000000 +#define __FSMCB 0xA0000000 /** FSMC register map base pointer */ -#define FSMC_BASE ((struct fsmc_reg_map*)__FSMC_B) +#define FSMC_BASE ((struct fsmc_reg_map*)__FSMCB) /** FSMC NOR/PSRAM register map type */ typedef struct fsmc_nor_psram_reg_map { @@ -97,16 +99,16 @@ typedef struct fsmc_nor_psram_reg_map { } fsmc_nor_psram_reg_map; /** FSMC NOR/PSRAM base pointer 1 */ -#define FSMC_NOR_PSRAM1_BASE ((struct fsmc_nor_psram_reg_map*)__FSMC_B) +#define FSMC_NOR_PSRAM1_BASE ((struct fsmc_nor_psram_reg_map*)__FSMCB) /** FSMC NOR/PSRAM base pointer 2 */ -#define FSMC_NOR_PSRAM2_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B + 0x8)) +#define FSMC_NOR_PSRAM2_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMCB + 0x8)) /** FSMC NOR/PSRAM base pointer 3 */ -#define FSMC_NOR_PSRAM3_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B+0x10)) +#define FSMC_NOR_PSRAM3_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMCB + 0x10)) /** FSMC NOR/PSRAM base pointer 4 */ -#define FSMC_NOR_PSRAM4_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMC_B+0x18)) +#define FSMC_NOR_PSRAM4_BASE ((struct fsmc_nor_psram_reg_map*)(__FSMCB + 0x18)) /* * Register bit definitions diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index c1f8d5c..fa36240 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -31,12 +31,20 @@ */ #include "maple_native.h" -#include "native_sram.h" + +#include "fsmc.h" +#include "gpio.h" +#include "rcc.h" +#include "timer.h" + +#include "wirish_types.h" #ifdef BOARD_maple_native +void initSRAMChip(void); + void boardInit(void) { - initNativeSRAM(); + initSRAMChip(); } extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { @@ -177,4 +185,15 @@ extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = { BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN }; +void initSRAMChip(void) { + fsmc_nor_psram_reg_map *regs = FSMC_NOR_PSRAM1_BASE; + + fsmc_sram_init_gpios(); + rcc_clk_enable(RCC_FSMC); + + regs->BCR = FSMC_BCR_WREN | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN; + fsmc_nor_psram_set_addset(regs, 0); + fsmc_nor_psram_set_datast(regs, 3); +} + #endif diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native.h index 2cbd406..b573d72 100644 --- a/wirish/boards/maple_native.h +++ b/wirish/boards/maple_native.h @@ -32,11 +32,6 @@ * See maple.h for more information on these definitions. */ -#include "gpio.h" -#include "timer.h" - -#include "wirish_types.h" - #ifndef _BOARD_MAPLE_NATIVE_H_ #define _BOARD_MAPLE_NATIVE_H_ diff --git a/wirish/native_sram.cpp b/wirish/native_sram.cpp deleted file mode 100644 index 5e8095f..0000000 --- a/wirish/native_sram.cpp +++ /dev/null @@ -1,45 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2011 LeafLabs, LLC. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ - -#include "native_sram.h" -#include "libmaple.h" -#include "fsmc.h" -#include "rcc.h" - -#ifdef BOARD_maple_native - -void initNativeSRAM(void) { - fsmc_nor_psram_reg_map *regs = FSMC_NOR_PSRAM1_BASE; - - fsmc_sram_init_gpios(); - rcc_clk_enable(RCC_FSMC); - - regs->BCR = FSMC_BCR_WREN | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN; - fsmc_nor_psram_set_addset(regs, 0); - fsmc_nor_psram_set_datast(regs, 3); -} - -#endif diff --git a/wirish/native_sram.h b/wirish/native_sram.h deleted file mode 100644 index 7724667..0000000 --- a/wirish/native_sram.h +++ /dev/null @@ -1,43 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2011 LeafLabs, LLC. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ - -#ifdef BOARD_maple_native - -#ifndef _NATIVE_SRAM_H_ -#define _NATIVE_SRAM_H_ - -/** - * Sets up the FSMC peripheral to use the SRAM chip on the Maple - * Native as an external segment of system memory space. - * - * This implementation is for the IS62WV51216BLL 8Mb chip (55ns - * timing, 512K x 16 bits). - */ -void initNativeSRAM(void); - -#endif - -#endif diff --git a/wirish/rules.mk b/wirish/rules.mk index 02906c7..c3608e3 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -30,8 +30,7 @@ cppSRCS_$(d) := wirish_math.cpp \ wirish_time.cpp \ pwm.cpp \ ext_interrupts.cpp \ - wirish_digital.cpp \ - native_sram.cpp + wirish_digital.cpp cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%) -- cgit v1.2.3 From 9ad170c63ddac17301566e69fe6a0e7a8d0d4639 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Mon, 2 May 2011 14:35:58 -0400 Subject: Fixing USBSerial::read(void*, uint32). --- wirish/usb_serial.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) (limited to 'wirish') diff --git a/wirish/usb_serial.cpp b/wirish/usb_serial.cpp index e2cdee3..e2751a2 100644 --- a/wirish/usb_serial.cpp +++ b/wirish/usb_serial.cpp @@ -103,18 +103,18 @@ uint32 USBSerial::available(void) { /* blocks forever until len_bytes is received */ uint32 USBSerial::read(void *buf, uint32 len) { - if (!buf) { + if (buf == 0) { return 0; } uint32 bytes_in = 0; while (len > 0) { - uint32 new_bytes = usbReceiveBytes((uint8*)((uint8*)buf+bytes_in), len); + uint32 new_bytes = usbReceiveBytes((uint8*)buf + bytes_in, len); len -= new_bytes; bytes_in += new_bytes; } - return len; + return bytes_in; } /* blocks forever until 1 byte is received */ -- cgit v1.2.3 From f3bcdd18d8f0b64cd8f17410b480b49315791544 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 4 May 2011 13:15:33 -0400 Subject: SerialUSB fixups. --- docs/source/lang/api/serialusb.rst | 15 +++-- libmaple/usb/usb.c | 12 ++-- libmaple/usb/usb.h | 2 +- libmaple/usb/usb_lib/usb_mem.c | 4 +- libmaple/usb/usb_lib/usb_mem.h | 2 +- wirish/Print.cpp | 2 +- wirish/Print.h | 4 +- wirish/usb_serial.cpp | 117 ++++++++++++++----------------------- wirish/usb_serial.h | 8 ++- 9 files changed, 67 insertions(+), 99 deletions(-) (limited to 'wirish') diff --git a/docs/source/lang/api/serialusb.rst b/docs/source/lang/api/serialusb.rst index ee7146e..ed466f2 100644 --- a/docs/source/lang/api/serialusb.rst +++ b/docs/source/lang/api/serialusb.rst @@ -16,9 +16,8 @@ Introduction In addition to three :ref:`serial ports `, the Maple's STM32 microprocessor includes a dedicated USB peripheral. This peripheral is used to emulate a regular serial port for use as a -terminal (text read/write). The emulated terminal is relatively slow -and inefficient; it is best for transferring data at regular serial -speeds (kilobaud). +terminal. The emulated terminal is relatively slow; it is best for +transferring data at regular serial speeds (kilobaud). Library access to the emulated serial port is provided through the ``SerialUSB`` object. You can mostly use ``SerialUSB`` as a drop-in @@ -30,14 +29,14 @@ replacement for ``Serial1``, ``Serial2``, and ``Serial3``. This means that if you have a number of calls to one of the ``SerialUSB`` ``write()`` or ``print()`` functions in your code, - and you are not monitoring the emulated on a computer, your program - will run much, much slower than if it is being monitored or totally - disconnected (run off of a battery). + and you are not monitoring ``SerialUSB`` on a computer, your + program will run much slower than if it is being monitored or + totally disconnected (run off of a battery). You can avoid this behavior by :ref:`deciphering the port status - using the DTR and RTS line status `; the + using the DTR and RTS line status ` (the behavior of these control lines is platform dependent and we no - longer interpret them by default. + longer interpret them by default). Library Documentation --------------------- diff --git a/libmaple/usb/usb.c b/libmaple/usb/usb.c index 7b1dd4c..b34c4b6 100644 --- a/libmaple/usb/usb.c +++ b/libmaple/usb/usb.c @@ -343,23 +343,21 @@ void usbBlockingSendByte(char ch) { countTx = 1; while (countTx); } -uint32 usbSendBytes(uint8* sendBuf, uint32 len) { - /* any checks on connection (via dtr/rts) done upstream in wirish or - by user */ - /* last xmit hasnt finished, abort */ +uint32 usbSendBytes(const uint8* sendBuf, uint32 len) { + /* Last transmission hasn't finished, abort */ if (countTx) { return 0; } // We can only put VCOM_TX_EPSIZE bytes in the buffer - if(len > VCOM_TX_EPSIZE/2) { - len = VCOM_TX_EPSIZE/2; + if (len > VCOM_TX_EPSIZE / 2) { + len = VCOM_TX_EPSIZE / 2; } // Try to load some bytes if we can if (len) { - UserToPMABufferCopy(sendBuf,VCOM_TX_ADDR, len); + UserToPMABufferCopy(sendBuf, VCOM_TX_ADDR, len); _SetEPTxCount(VCOM_TX_ENDP, len); countTx += len; _SetEPTxValid(VCOM_TX_ENDP); diff --git a/libmaple/usb/usb.h b/libmaple/usb/usb.h index 92f606c..c724c54 100644 --- a/libmaple/usb/usb.h +++ b/libmaple/usb/usb.h @@ -74,7 +74,7 @@ void usbWaitReset(void); /* blocking functions for send/receive */ void usbBlockingSendByte(char ch); -uint32 usbSendBytes(uint8* sendBuf,uint32 len); +uint32 usbSendBytes(const uint8* sendBuf,uint32 len); uint32 usbBytesAvailable(void); uint32 usbReceiveBytes(uint8* recvBuf, uint32 len); uint8 usbGetDTR(void); diff --git a/libmaple/usb/usb_lib/usb_mem.c b/libmaple/usb/usb_lib/usb_mem.c index ee698c5..90ffc62 100644 --- a/libmaple/usb/usb_lib/usb_mem.c +++ b/libmaple/usb/usb_lib/usb_mem.c @@ -30,9 +30,9 @@ * - wPMABufAddr: address into PMA. * - wNBytes: no. of bytes to be copied. * Output : None. -* Return : None . +* Return : None . *******************************************************************************/ -void UserToPMABufferCopy(u8 *pbUsrBuf, u16 wPMABufAddr, u16 wNBytes) +void UserToPMABufferCopy(const u8 *pbUsrBuf, u16 wPMABufAddr, u16 wNBytes) { u32 n = (wNBytes + 1) >> 1; /* n = (wNBytes + 1) / 2 */ u32 i, temp1, temp2; diff --git a/libmaple/usb/usb_lib/usb_mem.h b/libmaple/usb/usb_lib/usb_mem.h index a3d7927..60ff9f1 100644 --- a/libmaple/usb/usb_lib/usb_mem.h +++ b/libmaple/usb/usb_lib/usb_mem.h @@ -26,7 +26,7 @@ extern "C" { #endif -void UserToPMABufferCopy(u8 *pbUsrBuf, u16 wPMABufAddr, u16 wNBytes); +void UserToPMABufferCopy(const u8 *pbUsrBuf, u16 wPMABufAddr, u16 wNBytes); void PMAToUserBufferCopy(u8 *pbUsrBuf, u16 wPMABufAddr, u16 wNBytes); #if defined(__cplusplus) diff --git a/wirish/Print.cpp b/wirish/Print.cpp index cfb2cda..9130c9c 100644 --- a/wirish/Print.cpp +++ b/wirish/Print.cpp @@ -52,7 +52,7 @@ void Print::write(const char *str) { } } -void Print::write(void *buffer, uint32 size) { +void Print::write(const void *buffer, uint32 size) { uint8 *ch = (uint8*)buffer; while (size--) { write(*ch++); diff --git a/wirish/Print.h b/wirish/Print.h index ec7b163..73d82e7 100644 --- a/wirish/Print.h +++ b/wirish/Print.h @@ -35,9 +35,9 @@ enum { class Print { public: - virtual void write(uint8) = 0; + virtual void write(uint8 ch) = 0; virtual void write(const char *str); - virtual void write(void*, uint32); + virtual void write(const void *buf, uint32 len); void print(char); void print(const char[]); void print(uint8); diff --git a/wirish/usb_serial.cpp b/wirish/usb_serial.cpp index e2751a2..0a2be43 100644 --- a/wirish/usb_serial.cpp +++ b/wirish/usb_serial.cpp @@ -3,28 +3,29 @@ * * Copyright (c) 2010 Perry Hung. * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. *****************************************************************************/ /** - * @brief Wirish USB class for easy communication, uses libmaple's - * virtual com port implementation + * @brief USB virtual serial terminal */ #include @@ -34,7 +35,7 @@ #define USB_TIMEOUT 50 -USBSerial :: USBSerial(void) { +USBSerial::USBSerial(void) { } void USBSerial::begin(void) { @@ -46,54 +47,29 @@ void USBSerial::end(void) { } void USBSerial::write(uint8 ch) { - if(!(usbIsConnected() && usbIsConfigured())) { - return; - } - - uint16 status = 0; - uint32 start = millis(); - - while(status == 0 && (millis() - start <= USB_TIMEOUT)) { - status = usbSendBytes(&ch, 1); - } + const uint8 buf[] = {ch}; + this->write(buf, 1); } void USBSerial::write(const char *str) { - if(!(usbIsConnected() && usbIsConfigured())) { - return; - } - - uint32 len = strlen(str); - uint16 status = 0; - uint16 oldstatus = 0; - uint32 start = millis(); - - while(status < len && (millis() - start < USB_TIMEOUT)) { - status += usbSendBytes((uint8*)str+status, len-status); - if(oldstatus != status) - start = millis(); - oldstatus = status; - } + this->write(str, strlen(str)); } -void USBSerial::write(void *buf, uint32 size) { - if(!(usbIsConnected() && usbIsConfigured())) { +void USBSerial::write(const void *buf, uint32 len) { + if (!(usbIsConnected() && usbIsConfigured()) || !buf) { return; } - if (!buf) { - return; - } - - uint16 status = 0; - uint16 oldstatus = 0; + uint32 txed = 0; + uint32 old_txed = 0; uint32 start = millis(); - while(status < size && (millis() - start < USB_TIMEOUT)) { - status += usbSendBytes((uint8*)buf+status, size-status); - if(oldstatus != status) + while (txed < len && (millis() - start < USB_TIMEOUT)) { + txed += usbSendBytes((const uint8*)buf + txed, len - txed); + if (old_txed != txed) { start = millis(); - oldstatus = status; + } + old_txed = txed; } } @@ -101,47 +77,40 @@ uint32 USBSerial::available(void) { return usbBytesAvailable(); } -/* blocks forever until len_bytes is received */ uint32 USBSerial::read(void *buf, uint32 len) { - if (buf == 0) { + if (!buf) { return 0; } - uint32 bytes_in = 0; - while (len > 0) { - uint32 new_bytes = usbReceiveBytes((uint8*)buf + bytes_in, len); - len -= new_bytes; - bytes_in += new_bytes; + uint32 rxed = 0; + while (rxed < len) { + rxed += usbReceiveBytes((uint8*)buf + rxed, len - rxed); } - return bytes_in; + return rxed; } -/* blocks forever until 1 byte is received */ +/* Blocks forever until 1 byte is received */ uint8 USBSerial::read(void) { - uint8 ch; - - while (usbReceiveBytes(&ch, 1) == 0); - return ch; + uint8 buf[1]; + this->read(buf, 1); + return buf[0]; } uint8 USBSerial::pending(void) { return usbGetPending(); } -// TODO deprecate the crap out of this +uint8 USBSerial::isConnected(void) { + return usbIsConnected() && usbIsConfigured(); +} + uint8 USBSerial::getDTR(void) { return usbGetDTR(); } -// TODO deprecate the crap out of this uint8 USBSerial::getRTS(void) { return usbGetRTS(); } -uint8 USBSerial::isConnected(void) { - return (usbIsConnected() && usbIsConfigured()); -} - USBSerial SerialUSB; - diff --git a/wirish/usb_serial.h b/wirish/usb_serial.h index c228837..ba9e18c 100644 --- a/wirish/usb_serial.h +++ b/wirish/usb_serial.h @@ -23,8 +23,7 @@ *****************************************************************************/ /** - * @brief wirish usb class for easy goin communication, uses libmaple's - * virtual com port implementation + * @brief Wirish virtual serial port */ #ifndef _USB_SERIAL_H_ @@ -32,6 +31,9 @@ #include "Print.h" +/** + * @brief Virtual serial terminal. + */ class USBSerial : public Print { public: USBSerial(void); @@ -46,7 +48,7 @@ public: void write(uint8); void write(const char *str); - void write(void *, uint32); + void write(const void*, uint32); uint8 getRTS(); uint8 getDTR(); -- cgit v1.2.3 From 8ea79ddf6ab35ca48415d46f8c2ab09ed493b464 Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 4 May 2011 13:22:00 -0400 Subject: Making micros() counter underrun safe. Thanks, ala42! --- wirish/wirish_time.h | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) (limited to 'wirish') diff --git a/wirish/wirish_time.h b/wirish/wirish_time.h index a0b1c11..d5349e3 100644 --- a/wirish/wirish_time.h +++ b/wirish/wirish_time.h @@ -27,8 +27,8 @@ * @brief Timing and delay functions. */ -#ifndef _TIME_H -#define _TIME_H +#ifndef _TIME_H_ +#define _TIME_H_ #include "libmaple.h" #include "nvic.h" @@ -56,17 +56,15 @@ static inline uint32 micros(void) { uint32 cycle_cnt; uint32 res; - nvic_globalirq_disable(); - - cycle_cnt = systick_get_count(); - ms = millis(); - - nvic_globalirq_enable(); + do { + cycle_cnt = systick_get_count(); + ms = millis(); + } while (ms != millis()); /* SYSTICK_RELOAD_VAL is 1 less than the number of cycles it actually takes to complete a SysTick reload */ res = (ms * US_PER_MS) + - (SYSTICK_RELOAD_VAL + 1 - cycle_cnt)/CYCLES_PER_MICROSECOND; + (SYSTICK_RELOAD_VAL + 1 - cycle_cnt) / CYCLES_PER_MICROSECOND; return res; } @@ -96,4 +94,3 @@ void delay(unsigned long ms); void delayMicroseconds(uint32 us); #endif - -- cgit v1.2.3 From dde41df8c16fd92aa1b267383ae689c678e7758d Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 4 May 2011 13:36:52 -0400 Subject: Maple Mini pin map fix. Thanks, Xavier! --- wirish/boards/maple_mini.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp index 02d62c7..3bc250b 100644 --- a/wirish/boards/maple_mini.cpp +++ b/wirish/boards/maple_mini.cpp @@ -75,7 +75,7 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = { {GPIOA, NULL, NULL, 12, 0, ADCx}, /* D23/PA12 */ {GPIOA, TIMER1, NULL, 11, 4, ADCx}, /* D24/PA11 */ {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D25/PA10 */ - {GPIOA, TIMER2, NULL, 9, 2, ADCx}, /* D26/PA9 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D26/PA9 */ {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D27/PA8 */ {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D28/PB15 */ {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D29/PB14 */ -- cgit v1.2.3 From f35c9f71385ba0629e1e3744d08da2cf442b3e9d Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Wed, 4 May 2011 17:23:54 -0400 Subject: SPI fixups. Initial post-review changes based on thread here: https://github.com/leaflabs/libmaple/commit/77f707d7b87fce284945fc9fe21c824c18c4c93d#comments --- libmaple/spi.c | 75 ++++++++++++++++++--------------------------- libmaple/spi.h | 20 +++++------- wirish/comm/HardwareSPI.cpp | 33 ++++++-------------- wirish/comm/HardwareSPI.h | 2 +- 4 files changed, 47 insertions(+), 83 deletions(-) (limited to 'wirish') diff --git a/libmaple/spi.c b/libmaple/spi.c index 2fbc2ac..e58ae91 100644 --- a/libmaple/spi.c +++ b/libmaple/spi.c @@ -34,6 +34,8 @@ #include "spi.h" #include "bitband.h" +static void spi_reconfigure(spi_dev *dev, uint32 cr1_config); + /* * SPI devices */ @@ -75,28 +77,9 @@ void spi_init(spi_dev *dev) { } /** - * @brief Configure GPIO bit modes for use as a SPI bus master's pins. - * @param nss_dev NSS pin's GPIO device - * @param comm_dev SCK, MISO, MOSI pins' GPIO device - * @param nss_bit NSS pin's GPIO bit on nss_dev - * @param sck_bit SCK pin's GPIO bit on comm_dev - * @param miso_bit MISO pin's GPIO bit on comm_dev - * @param mosi_bit MOSI pin's GPIO bit on comm_dev - */ -void spi_master_gpio_cfg(gpio_dev *nss_dev, - gpio_dev *comm_dev, - uint8 nss_bit, - uint8 sck_bit, - uint8 miso_bit, - uint8 mosi_bit) { - gpio_set_mode(nss_dev, nss_bit, GPIO_AF_OUTPUT_PP); - gpio_set_mode(comm_dev, sck_bit, GPIO_AF_OUTPUT_PP); - gpio_set_mode(comm_dev, miso_bit, GPIO_INPUT_FLOATING); - gpio_set_mode(comm_dev, mosi_bit, GPIO_AF_OUTPUT_PP); -} - -/** - * @brief Configure GPIO bit modes for use as a SPI bus slave's pins. + * @brief Configure GPIO bit modes for use as a SPI port's pins. + * @param as_master If true, configure bits for use as a bus master. + * Otherwise, configure bits for use as slave. * @param nss_dev NSS pin's GPIO device * @param comm_dev SCK, MISO, MOSI pins' GPIO device * @param nss_bit NSS pin's GPIO bit on nss_dev @@ -104,20 +87,26 @@ void spi_master_gpio_cfg(gpio_dev *nss_dev, * @param miso_bit MISO pin's GPIO bit on comm_dev * @param mosi_bit MOSI pin's GPIO bit on comm_dev */ -void spi_slave_gpio_cfg(gpio_dev *nss_dev, - gpio_dev *comm_dev, - uint8 nss_bit, - uint8 sck_bit, - uint8 miso_bit, - uint8 mosi_bit) { - gpio_set_mode(nss_dev, nss_bit, GPIO_INPUT_FLOATING); - gpio_set_mode(comm_dev, sck_bit, GPIO_INPUT_FLOATING); - gpio_set_mode(comm_dev, miso_bit, GPIO_AF_OUTPUT_PP); - gpio_set_mode(comm_dev, mosi_bit, GPIO_INPUT_FLOATING); +void spi_gpio_cfg(uint8 as_master, + gpio_dev *nss_dev, + uint8 nss_bit, + gpio_dev *comm_dev, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit) { + if (as_master) { + gpio_set_mode(nss_dev, nss_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, sck_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, miso_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, mosi_bit, GPIO_AF_OUTPUT_PP); + } else { + gpio_set_mode(nss_dev, nss_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, sck_bit, GPIO_INPUT_FLOATING); + gpio_set_mode(comm_dev, miso_bit, GPIO_AF_OUTPUT_PP); + gpio_set_mode(comm_dev, mosi_bit, GPIO_INPUT_FLOATING); + } } -static void spi_reconfigure(spi_dev *dev, uint32 cr1_config); - /** * @brief Configure and enable a SPI device as bus master. * @@ -154,23 +143,19 @@ void spi_slave_enable(spi_dev *dev, spi_mode mode, uint32 flags) { * @brief Nonblocking SPI transmit. * @param dev SPI port to use for transmission * @param buf Buffer to transmit. The sizeof buf's elements are - * inferred from the dev's data frame format (i.e., are + * inferred from dev's data frame format (i.e., are * correctly treated as 8-bit or 16-bit quantities). * @param len Maximum number of elements to transmit. * @return Number of elements transmitted. */ uint32 spi_tx(spi_dev *dev, const void *buf, uint32 len) { - spi_reg_map *regs = dev->regs; uint32 txed = 0; - if (spi_dff(dev) == SPI_DFF_16_BIT) { - const uint8 *buf8 = (const uint8*)buf; - while ((regs->SR & SPI_SR_TXE) && (txed < len)) { - regs->DR = buf8[txed++]; - } - } else { - const uint16 *buf16 = (const uint16*)buf; - while ((regs->SR & SPI_SR_TXE) && (txed < len)) { - regs->DR = buf16[txed++]; + uint8 byte_frame = spi_dff(dev) == SPI_DFF_8_BIT; + while (spi_is_tx_empty(dev) && (txed < len)) { + if (byte_frame) { + dev->regs->DR = ((const uint8*)buf)[txed++]; + } else { + dev->regs->DR = ((const uint16*)buf)[txed++]; } } return txed; diff --git a/libmaple/spi.h b/libmaple/spi.h index e2820dd..5c8728f 100644 --- a/libmaple/spi.h +++ b/libmaple/spi.h @@ -222,19 +222,13 @@ extern spi_dev *SPI3; void spi_init(spi_dev *dev); -void spi_master_gpio_cfg(gpio_dev *nss_dev, - gpio_dev *comm_dev, - uint8 nss_bit, - uint8 sck_bit, - uint8 miso_bit, - uint8 mosi_bit); - -void spi_slave_gpio_cfg(gpio_dev *nss_dev, - gpio_dev *comm_dev, - uint8 nss_bit, - uint8 sck_bit, - uint8 miso_bit, - uint8 mosi_bit); +void spi_gpio_cfg(uint8 as_master, + gpio_dev *nss_dev, + uint8 nss_bit, + gpio_dev *comm_dev, + uint8 sck_bit, + uint8 miso_bit, + uint8 mosi_bit); /** * @brief SPI mode configuration. diff --git a/wirish/comm/HardwareSPI.cpp b/wirish/comm/HardwareSPI.cpp index 1b36d21..54b7ab3 100644 --- a/wirish/comm/HardwareSPI.cpp +++ b/wirish/comm/HardwareSPI.cpp @@ -125,11 +125,10 @@ void HardwareSPI::read(uint8 *buf, uint32 len) { } void HardwareSPI::write(uint8 byte) { - uint8 buf[] = {byte}; - this->write(buf, 1); + this->write(&byte, 1); } -void HardwareSPI::write(uint8 *data, uint32 length) { +void HardwareSPI::write(const uint8 *data, uint32 length) { uint32 txed = 0; while (txed < length) { txed += spi_tx(this->spi_d, data + txed, length - txed); @@ -152,7 +151,6 @@ uint8 HardwareSPI::send(uint8 data) { uint8 HardwareSPI::send(uint8 *buf, uint32 len) { if (len == 0) { - ASSERT(0); return 0; } uint32 txed = 0; @@ -183,11 +181,6 @@ static void enable_device(spi_dev *dev, SPIFrequency freq, spi_cfg_flag endianness, spi_mode mode) { - if (freq >= MAX_SPI_FREQS) { - ASSERT(0); - return; - } - spi_baud_rate baud = determine_baud_rate(dev, freq); uint32 cfg_flags = (endianness | SPI_DFF_8_BIT | SPI_SW_SLAVE | (as_master ? SPI_SOFT_SS : 0)); @@ -261,21 +254,13 @@ static void configure_gpios(spi_dev *dev, bool as_master) { disable_pwm(misoi); disable_pwm(mosii); - if (as_master) { - spi_master_gpio_cfg(nssi->gpio_device, - scki->gpio_device, - nssi->gpio_bit, - scki->gpio_bit, - misoi->gpio_bit, - mosii->gpio_bit); - } else { - spi_slave_gpio_cfg(nssi->gpio_device, - scki->gpio_device, - nssi->gpio_bit, - scki->gpio_bit, - misoi->gpio_bit, - mosii->gpio_bit); - } + spi_gpio_cfg(as_master, + nssi->gpio_device, + nssi->gpio_bit, + scki->gpio_device, + scki->gpio_bit, + misoi->gpio_bit, + mosii->gpio_bit); } static const spi_baud_rate baud_rates[MAX_SPI_FREQS] __FLASH__ = { diff --git a/wirish/comm/HardwareSPI.h b/wirish/comm/HardwareSPI.h index 1b2a966..3a6def5 100644 --- a/wirish/comm/HardwareSPI.h +++ b/wirish/comm/HardwareSPI.h @@ -140,7 +140,7 @@ public: * @param buffer Bytes to transmit. * @param length Number of bytes in buffer to transmit. */ - void write(uint8 *buffer, uint32 length); + void write(const uint8 *buffer, uint32 length); /** * @brief Transmit a byte, then return the next unread byte. -- cgit v1.2.3 From ef8c58b96ea8d1e503362c5d18a74cd5d0101e0c Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Thu, 5 May 2011 15:38:58 -0400 Subject: Renaming "enum ExtIntTriggerMode_" -> "enum ExtIntTriggerMode". Done for consistency the rest of the source. Doesn't affect any documented features. --- wirish/ext_interrupts.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'wirish') diff --git a/wirish/ext_interrupts.h b/wirish/ext_interrupts.h index 364bcda..7d20801 100644 --- a/wirish/ext_interrupts.h +++ b/wirish/ext_interrupts.h @@ -38,7 +38,7 @@ * The kind of transition on an external pin which should trigger an * interrupt. */ -typedef enum ExtIntTriggerMode_ { +typedef enum ExtIntTriggerMode { RISING, /**< To trigger an interrupt when the pin transitions LOW to HIGH */ FALLING, /**< To trigger an interrupt when the pin transitions -- cgit v1.2.3 From 6765e0eaf8da078195373e297acc9dff6dde7b9e Mon Sep 17 00:00:00 2001 From: Marti Bolivar Date: Thu, 5 May 2011 17:18:25 -0400 Subject: Putting updated HardwareTimer back into the build. HardwareTimer was removed from the build when the timer refactor was done; this redoes it in terms of the new timer.h interface. A variety of conflicting or badly designed bits were deprecated or removed. I'm still not satisfied with this interface, as it's going to make life difficult moving forward to high-density chips, where the addition of basic timers means that the capture/compare methods won't apply in some cases. However, we need to get 0.0.10 out the door, so it'll have to do for now. The docs are up to date, and contain a warning that the Wirish API isn't stable and a recommendation to use libmaple proper. --- docs/source/lang/api/analogwrite.rst | 24 +- docs/source/lang/api/hardwaretimer.rst | 579 +++++++++++++-------------------- docs/source/timers.rst | 10 + wirish/HardwareTimer.cpp | 217 ++++-------- wirish/HardwareTimer.h | 430 ++++++++++-------------- wirish/rules.mk | 1 + wirish/wirish.h | 1 + 7 files changed, 500 insertions(+), 762 deletions(-) (limited to 'wirish') diff --git a/docs/source/lang/api/analogwrite.rst b/docs/source/lang/api/analogwrite.rst index e789305..dd2192a 100644 --- a/docs/source/lang/api/analogwrite.rst +++ b/docs/source/lang/api/analogwrite.rst @@ -52,7 +52,7 @@ you much more precise control over the duty cycle of your PWM output. If you're porting code from the Arduino and want a quick-and-dirty fix, one solution is to :ref:`map ` the argument to -analogWrite into the right range:: +analogWrite() into the right range:: // Arduino code: analogWrite(pin, duty); @@ -71,8 +71,8 @@ that Timer's overflow to 255. Subsequent calls to analogWrite() should work as on the Arduino (with the same loss of precision). Note, however, that that affects the overflow for the **entire timer**, so other code relying on that timer (such as any -:ref:`interrupts ` the timer controls) will -likely need to be modified as well. +:ref:`interrupts ` the timer controls) +will likely need to be modified as well. Difference 2: You must use pinMode() to set up PWM ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -141,23 +141,27 @@ the steps are: 1. Figure out which :ref:`timer ` controls PWM output on your pin (\ :ref:`your board's Timer Pin Map - ` is your friend here). Let's say it's ``Timern``\ - , where ``n`` is some number 1, 2, 3, or 4. + ` is your friend here). -2. Call ``Timern.setPeriod(2041)``\ . This will set the timer's - period to approximately 2041 microseconds, which is a frequency of - approximately 490 Hz. +2. Let's say it's timer ``n``, where ``n`` is some number. You'll + then need to put "``HardwareTimer timer(n);``" with your variables, + as described in the :ref:`HardwareTimer + ` reference. + +3. In your :ref:`lang-setup`, put "``timer.setPeriod(2041);``". This + will set the timer's period to approximately 2041 microseconds, + which is a frequency of approximately 490 Hz. Be aware that this will change the period for the **entire timer**\ , and will affect anything else in your program that depends on that timer. The important examples are :ref:`timer interrupts -` and :ref:`PWM +` and :ref:`PWM `\ . See Also -------- -- :ref:`Maple PWM tutorial ` +- :ref:`pwm` .. rubric:: Footnotes diff --git a/docs/source/lang/api/hardwaretimer.rst b/docs/source/lang/api/hardwaretimer.rst index 526beb6..09245f0 100644 --- a/docs/source/lang/api/hardwaretimer.rst +++ b/docs/source/lang/api/hardwaretimer.rst @@ -5,456 +5,341 @@ HardwareTimer ============= -This class defines the public API for interfacing with the STM32's -built-in timer peripherals. More information on these peripherals -(including code examples) is available in the :ref:`timers reference -`. +This page describes how to control the built-in timers. It does not +describe how the timers work on your board. For more information on +that, the :ref:`timers reference `. -.. FIXME [0.0.10] Updated HardwareTimer documentation, with deprecation +.. warning:: The timer interface is still taking shape, and is + expected to change significantly between releases. Because of + that, the functionality described in this page shouldn't be + considered stable. -.. warning:: This class has been deprecated. It is not available in - the current build. + If you want a timer API that will be consistent between releases of + the Maple IDE, your best bet for now is to use the low-level + support in :ref:`libmaple-timer`. -Library Documentation ---------------------- +.. contents:: Contents + :local: -HardwareTimer Class Reference -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +.. _lang-hardwaretimer-getting-started: -To interact with a particular timer, call one of the methods -documented below on one of the predefined ``HardwareTimer`` instances. -For example, to set the prescale factor on timer 1 to 5, call -``Timer1.setPrescaleFactor(5)``. +Getting Started +--------------- -.. TODO add tutorial-style examples +You'll first need to define a ``HardwareTimer`` variable, which you'll +use to control the timer. Do this by putting the line +"``HardwareTimer timer(number);``" with your variables, where +``number`` is the timer's number. -.. cpp:class:: HardwareTimer +Here's an example (we'll fill in :ref:`setup() ` and +:ref:`loop() ` later):: - Class for interacting with a timer. There are four predefined - instances available on the Maple: ``Timer1``, ``Timer2``, - ``Timer3``, and ``Timer4``. + // Use timer 1 + HardwareTimer timer(1); -.. _lang-hardwaretimer-attachinterrupt: + void setup() { + // Your setup code + } -.. cpp:function:: void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) + void loop() { + // ... + } - Attach an interrupt handler to the given ``channel``. This - interrupt handler will be called when the timer's counter reaches - the given channel :ref:`compare ` - value. +Configuring the Prescaler and Overflow +-------------------------------------- - ``handler`` should be a function which takes no arguments and has - :ref:`void ` value; i.e. it should have signature :: +After defining your ``timer`` variable, you'll probably want to +configure how fast your timer's counter changes (using the prescaler) +and when it gets reset to zero (using the overflow value). You can do +that with the ``setPrescaleFactor()`` and ``setOverflow()`` functions. - void handler(void); - - You can later detach the interrupt using :ref:`detachInterrupt() - `. - - .. note:: The function (often called an *interrupt service - routine*, or ISR) should attempt to return as quickly as - possible. :ref:`Blinking the LED `, some - logic, :ref:`PWM ` updates, and :ref:`Serial - ` writes are fine; writing to - :ref:`SerialUSB ` or :ref:`waiting - ` for user input can take a long - time and prevent other interrupts from firing on time. - - Tip: if you have a :ref:`delay() ` in your - ISR, you're probably doing it wrong. - -.. cpp:function:: void HardwareTimer::attachCompare1Interrupt(voidFuncPtr handler) - - Equivalent to :ref:`attachInterrupt - `\ ``(1, handler)``. - -.. cpp:function:: void HardwareTimer::attachCompare2Interrupt(voidFuncPtr handler) - - Equivalent to :ref:`attachInterrupt - `\ ``(2, handler)``. - -.. cpp:function:: void HardwareTimer::attachCompare3Interrupt(voidFuncPtr handler) - - Equivalent to :ref:`attachInterrupt - `\ ``(3, handler)``. - -.. cpp:function:: void HardwareTimer::attachCompare4Interrupt(voidFuncPtr handler) - - Equivalent to :ref:`attachInterrupt - `\ ``(4, handler)``. - -.. _lang-hardwaretimer-setchannelmode: - -.. cpp:function:: void HardwareTimer::setChannelMode(int channel, TimerMode mode) - - Set the given channel of this timer to the given :ref:`mode - `. The parameter ``channel`` is one of - 1, 2, 3, and 4, and corresponds to the compare channel you would - like to set. Refer to your board's :ref:`master pin map - ` to match up timer channels and pin numbers. - -.. cpp:function:: void HardwareTimer::setChannel1Mode(TimerMode mode) - - Equivalent to :ref:`setChannelMode `\ - ``(1, mode)``. - -.. cpp:function:: void HardwareTimer::setChannel2Mode(TimerMode mode) - - Equivalent to :ref:`setChannelMode `\ - ``(2, mode)``. - -.. cpp:function:: void HardwareTimer::setChannel3Mode(TimerMode mode) - - Equivalent to :ref:`setChannelMode `\ - ``(3, mode)``. - -.. cpp:function:: void HardwareTimer::setChannel4Mode(TimerMode mode) - - Equivalent to :ref:`setChannelMode `\ - ``(4, mode)``. - -.. _lang-hardwaretimer-getcompare: - -.. cpp:function:: uint16 HardwareTimer::getCompare(int channel) - - Gets the compare value for the given ``channel``, from 1 to 4. See - :ref:`setCompare() `. - -.. cpp:function:: uint16 HardwareTimer::getCompare1() - - Equivalent to :ref:`getCompare `\ - ``(1, mode)``. - -.. cpp:function:: uint16 HardwareTimer::getCompare2() - - Equivalent to :ref:`getCompare `\ - ``(2, mode)``. - -.. cpp:function:: uint16 HardwareTimer::getCompare3() - - Equivalent to :ref:`getCompare `\ - ``(3, mode)``. - -.. cpp:function:: uint16 HardwareTimer::getCompare4() +.. _lang-hardwaretimer-setprescalefactor: - Equivalent to :ref:`getCompare `\ - ``(4, mode)``. +.. doxygenfunction:: HardwareTimer::setPrescaleFactor + :no-link: -.. _lang-hardwaretimer-setcompare: +.. _lang-hardwaretimer-setoverflow: -.. cpp:function:: void HardwareTimer::setCompare(int channel, uint16 compare) +.. doxygenfunction:: HardwareTimer::setOverflow + :no-link: - Sets the compare value for the given ``channel`` to ``compare``. - If ``compare`` is greater than this timer's overflow value, it will - be truncated to the overflow value. The default compare value is - 65,535 (the largest unsigned 16-bit integer value). +For example:: - When the counter reaches this value the interrupt for this channel - will fire if the given ``channel`` :ref:`mode - ` is ``TIMER_OUTPUTCOMPARE`` and - an interrupt is :ref:`attached - `. + // Use timer 1 + HardwareTimer timer(1); - By default, this only changes the relative offsets between events - on a single timer ("phase"); they don't control the frequency with - which they occur. However, a common trick is to increment the - compare value manually in the interrupt handler so that the event - will fire again after the increment period. There can be a - different increment value for each channel, so this trick allows - events to be programmed at 4 different rates on a single - timer. Note that function call overheads mean that the smallest - increment rate is at least a few microseconds. + void setup() { + timer.setPrescaleFactor(5); + timer.setOverflow(255); + } -.. cpp:function:: void HardwareTimer::setCompare1(uint16 compare) + void loop() { + // ... + } - Equivalent to :ref:`setCompare `\ - ``(1, compare)``. +You may also find the ``setPeriod()`` function useful: -.. cpp:function:: void HardwareTimer::setCompare2(uint16 compare) +.. _lang-hardwaretimer-setperiod: - Equivalent to :ref:`setCompare `\ - ``(2, compare)``. +.. doxygenfunction:: HardwareTimer::setPeriod + :no-link: -.. cpp:function:: void HardwareTimer::setCompare3(uint16 compare) +For example:: - Equivalent to :ref:`setCompare `\ - ``(3, compare)``. + // Use timer 1 + HardwareTimer timer(1); -.. cpp:function:: void HardwareTimer::setCompare4(uint16 compare) + void setup() { + // Have the timer repeat every 20 milliseconds + int microseconds_per_millisecond = 1000; + timer.setPeriod(20 * microseconds_per_millisecond); + } - Equivalent to :ref:`setCompare `\ - ``(4, compare)``. + void loop() { + // ... + } -.. cpp:function:: uint16 HardwareTimer::getCount() +.. _lang-hardwaretimer-interrupts: - Gets the current timer count. Due to function call overhead, the - return value will be increasingly accurate with smaller prescale - values. Also see :ref:`setCount() `. +Using Timer Interrupts +---------------------- -.. _lang-hardwaretimer-setcount: +.. TODO [0.2.0] Improve the interrupts section, here or in timers.rst -.. cpp:function:: void HardwareTimer::setCount(uint16 val) +In order to use timer interrupts, we recommend the following sequence: - Set the timer's current count to ``val``. +* Pause the timer. +* Configure the prescaler and overflow. +* Pick a timer channel to handle the interrupt and set the channel's + :ref:`mode ` to ``TIMER_OUTPUT_COMPARE``. +* Set the channel compare value appropriately (this controls what counter value, + from 0 to overflow - 1). If you just want to make the interrupt fire once + every time the timer overflows, and you don't care what the timer count is, + the channel compare value can just be 1. +* Attach an interrupt handler to the channel. +* Refresh the timer. +* Resume the timer. - Note that there is some function call overhead associated with - calling this method, so using it is not a robust way to get - multiple timers to share a count value. +Here are two complete examples. - If ``val`` exceeds the timer's :ref:`overflow value - `, it is truncated to the overflow - value. +**LED blink**: This example blinks the built-in LED without doing +anything in ``loop()``. :: + #define LED_RATE 500000 // in microseconds; should give 0.5Hz toggles -.. _lang-hardwaretimer-detachinterrupt: - -.. cpp:function:: void HardwareTimer::detachInterrupt(int channel) + // We'll use timer 2 + HardwareTimer timer(2); - Remove the interrupt handler attached to the given ``channel``, if - any. The handler will no longer be called by this timer. + void setup() { + // Set up the LED to blink + pinMode(BOARD_LED_PIN, OUTPUT); -.. cpp:function:: void HardwareTimer::detachCompare1Interrupt() + // Pause the timer while we're configuring it + timer.pause(); - Equivalent to :ref:`detachInterrupt - `\ ``(1)``. + // Set up period + timer.setPeriod(LED_RATE); // in microseconds -.. cpp:function:: void HardwareTimer::detachCompare2Interrupt() + // Set up an interrupt on channel 1 + timer.setChannel1Mode(TIMER_OUTPUT_COMPARE); + timer.setCompare(TIMER_CH1, 1); // Interrupt 1 count after each update + timer.attachCompare1Interrupt(handler_led); - Equivalent to :ref:`detachInterrupt - `\ ``(2)``. + // Refresh the timer's count, prescale, and overflow + timer.refresh(); -.. cpp:function:: void HardwareTimer::detachCompare3Interrupt() + // Start the timer counting + timer.resume(); + } - Equivalent to :ref:`detachInterrupt - `\ ``(3)``. + void loop() { + // Nothing! It's all in the handler_led() interrupt: + } -.. cpp:function:: void HardwareTimer::detachCompare4Interrupt() + void handler_led(void) { + toggleLED(); + } - Equivalent to :ref:`detachInterrupt - `\ ``(4)``. +**Racing Counters**: This example shows how to use multiple timers at +the same time. :: -.. _lang-hardwaretimer-generateupdate: + int count3 = 0; + int count4 = 0; -.. cpp:function:: void HardwareTimer::generateUpdate() + // We'll use timers 3 and 4 + HardwareTimer timer3(3); + HardwareTimer timer4(4); - Re-initializes the counter (to 0 in upcounting mode, which is the - default), and generates an update of the prescale and overflow - registers. + void setup() { + // Set up the button for input + pinMode(BOARD_BUTTON_PIN, INPUT_PULLUP); -.. _lang-hardwaretimer-getoverflow: + // Set up timers to add 1 to their counts each time + // their interrupts fire. + timer3.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer4.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE); + timer3.pause(); + timer4.pause(); + timer3.setCount(0); + timer4.setCount(0); + timer3.setOverflow(30000); + timer4.setOverflow(30000); + timer3.setCompare(TIMER_CH1, 1000); // somewhere in the middle + timer4.setCompare(TIMER_CH1, 1000); + timer3.attachCompare1Interrupt(handler3); + timer4.attachCompare1Interrupt(handler4); + timer3.refresh(); + timer4.refresh(); + timer3.resume(); + timer4.resume(); + } -.. cpp:function:: uint16 HardwareTimer::getOverflow() + void loop() { + // Display the running counts + SerialUSB.print("Count 3: "); + SerialUSB.print(count3); + SerialUSB.print("\t\tCount 4: "); + SerialUSB.println(count4); + + // While the button is held down, pause timer 4 + for (int i = 0; i < 1000; i++) { + if (digitalRead(BOARD_BUTTON_PIN)) { + timer4.pause(); + } else { + timer4.resume(); + } + delay(1); + } + } - Gets the timer's overflow value. See :ref:`setOverflow() - `. + void handler3(void) { + count3++; + } -.. _lang-hardwaretimer-setoverflow: + void handler4(void) { + count4++; + } -.. cpp:function:: void HardwareTimer::setOverflow(uint16 val) +``HardwareTimer`` Class Reference +--------------------------------- - Sets the timer overflow (or "reload") value to ``val``. +This section gives a full listing of the capabilities of a +``HardwareTimer``. - When the timer's counter reaches this, value it resets to - zero. Its default value is 65535 (the largest unsigned 16-bit - integer); setting the overflow to anything lower will cause - interrupts to be called more frequently (see :ref:`setPeriod() - ` function for a shortcut). +.. doxygenclass:: HardwareTimer + :members: HardwareTimer, pause, resume, getPrescaleFactor, setPrescaleFactor, getOverflow, setOverflow, getCount, setCount, setPeriod, setMode, getCompare, setCompare, attachInterrupt, detachInterrupt, refresh - After the next :ref:`timer update - `, this number will be the - maximum value for the timer's channel compare values. +.. _lang-hardwaretimer-timermode: -.. _lang-hardwaretimer-pause: +.. doxygenenum:: timer_mode -.. cpp:function:: void HardwareTimer::pause() +Deprecated Functionality +------------------------ - Stop the timer's counter, without affecting its configuration. +The following functionality exists for now, but it has been +deprecated, and will be removed in a future Maple IDE release. You +shouldn't use it in new programs, and you should change any of your +programs which do use them to use the up-to-date features described +above. - The timer will no longer count or fire interrupts after this - function is called, until it is resumed. This function is useful - during timer setup periods, in order to prevent interrupts from - firing before the timer is fully configured. +The ``TimerMode`` type from previous releases has been renamed +``timer_mode``. The mode ``TIMER_OUTPUTCOMPARE`` is still present, +but will be removed in a future release. Use ``TIMER_OUTPUT_COMPARE`` +instead. - Note that there is some function call overhead associated with this - method, so using it in concert with :ref:`resume() - ` is not a robust way to align multiple - timers to the same count value. +.. cpp:function:: void HardwareTimer::attachCompare1Interrupt(voidFuncPtr handler) -.. _lang-hardwaretimer-setperiod: + Use ``attachInterrupt(1, handler)`` instead. -.. cpp:function:: uint16 HardwareTimer::setPeriod(uint32 microseconds) +.. cpp:function:: void HardwareTimer::attachCompare2Interrupt(voidFuncPtr handler) - Configure the :ref:`prescaler - ` and :ref:`overflow - ` values to generate a timer reload - with a period as close to the given number of ``microseconds`` as - possible. + Use ``attachInterrupt(2, handler)`` instead. - The return value is the new overflow value, which may be used to - set channel compare values. However, if a clock that fires an - interrupt every given number of microseconds is all that is - desired, and the relative "phases" are unimportant, channel compare - values may all be set to 1. +.. cpp:function:: void HardwareTimer::attachCompare3Interrupt(voidFuncPtr handler) -.. _lang-hardwaretimer-getprescalefactor: + Use ``attachInterrupt(3, handler)`` instead. -.. cpp:function:: uint16 HardwareTimer::getPrescaleFactor() +.. cpp:function:: void HardwareTimer::attachCompare4Interrupt(voidFuncPtr handler) - Returns the timer's prescale factor. See - :ref:`setPrescaleFactor() `. + Use ``attachInterrupt(4, handler)`` instead. -.. _lang-hardwaretimer-setprescalefactor: +.. _lang-hardwaretimer-setchannelmode: -.. cpp:function:: void HardwareTimer::setPrescaleFactor(uint16 factor) +.. cpp:function:: void HardwareTimer::setChannelMode(int channel, timer_mode mode) - Set the timer's prescale factor to ``factor``. + Use ``setMode(channel, mode)`` instead. - The prescaler acts as a clock divider to slow down the rate at - which the counter increments. +.. cpp:function:: void HardwareTimer::setChannel1Mode(timer_mode mode) - For example, the system clock rate is 72MHz, so the counter will - reach 65535 in (13.89 nanoseconds) × (65535 counts) = (910.22 - microseconds), or about a thousand times a second. If the - prescaler equals 1098, then the clock rate is effectively 72MHz / - 1098 = 65.56KHz, and the counter will reach 65536 in (15.25 - microseconds) × (65536 counts) = (0.999 seconds), or about once - per second. + Use ``setMode(1, mode)`` instead. - The :ref:`setPeriod() ` method may - also be used as a convenient alternative. +.. cpp:function:: void HardwareTimer::setChannel2Mode(timer_mode mode) -.. _lang-hardwaretimer-resume: + Use ``setMode(2, mode)`` instead. -.. cpp:function:: void HardwareTimer::resume() +.. cpp:function:: void HardwareTimer::setChannel3Mode(timer_mode mode) - Resume a paused timer, without affecting its configuration. + Use ``setMode(3, mode)`` instead. - The timer will resume counting and firing interrupts as - appropriate. +.. cpp:function:: void HardwareTimer::setChannel4Mode(timer_mode mode) - Note that there is some function call overhead associated with - using this method, so using it in concert with :ref:`pause() - ` is not a robust way to align multiple - timers to the same count value. + Use ``setMode(4, mode)`` instead. -.. cpp:function:: timer_dev_num HardwareTimer::getTimerNum() +.. cpp:function:: uint16 HardwareTimer::getCompare1() - Returns the :ref:`timer device number - ` associated with the timer. For - example, ``Timer1.getTimerNum()`` would return ``TIMER1``. + Use ``getCompare(1, mode)`` instead. - In most cases, you should not need to use this function. If you do - use it, be careful; the constant ``TIMER1`` is *not equal* to the - number 1; similarly, ``TIMER2`` is *not* the number 2, etc. Be - sure to refer to the timer device number by name. +.. cpp:function:: uint16 HardwareTimer::getCompare2() -.. _lang-hardwaretimer-modes: + Use ``getCompare(2, mode)`` instead. -Timer Modes -^^^^^^^^^^^ -.. doxygenenum:: TimerMode +.. cpp:function:: uint16 HardwareTimer::getCompare3() -.. _lang-hardwaretimer-timer-dev-num: + Use ``getCompare(3, mode)`` instead. -Timer Device Numbers -^^^^^^^^^^^^^^^^^^^^ +.. cpp:function:: uint16 HardwareTimer::getCompare4() -These provide a lower-level interface for interacting with timers. -They are mostly useful in context with the :ref:`getTimer() -` function. **Be careful** when using -these not to confuse e.g. ``TIMER1`` with the number 1; they are -different. + Use ``getCompare(4, mode)`` instead. -.. doxygenenum:: timer_dev_num +.. cpp:function:: void HardwareTimer::setCompare1(uint16 compare) -.. _lang-hardwaretimer-convenience: + Use ``setCompare(1, compare)`` instead. -.. _lang-hardwaretimer-gettimer: +.. cpp:function:: void HardwareTimer::setCompare2(uint16 compare) -Other Functions -^^^^^^^^^^^^^^^ -.. doxygenfunction:: getTimer + Use ``setCompare(2, compare)`` instead. -Examples -^^^^^^^^ +.. cpp:function:: void HardwareTimer::setCompare3(uint16 compare) -**LED blink**:: + Use ``setCompare(3, compare)`` instead. - #define LED_RATE 500000 // in microseconds; should give 0.5Hz toggles +.. cpp:function:: void HardwareTimer::setCompare4(uint16 compare) - void handler_led(void); + Use ``setCompare(4, compare)`` instead. - void setup() - { - // Set up the LED to blink - pinMode(BOARD_LED_PIN, OUTPUT); +.. cpp:function:: void HardwareTimer::detachCompare1Interrupt() - // Setup Timer - Timer2.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer2.setPeriod(LED_RATE); // in microseconds - Timer2.setCompare1(1); // overflow might be small - Timer2.attachCompare1Interrupt(handler_led); - } + Use ``detachInterrupt(1)`` instead. - void loop() { - // Nothing! It's all in the interrupts - } +.. cpp:function:: void HardwareTimer::detachCompare2Interrupt() - void handler_led(void) { - toggleLED(); - } + Use ``detachInterrupt(2)`` instead. -**Racing Counters**:: +.. cpp:function:: void HardwareTimer::detachCompare3Interrupt() - void handler_count1(void); - void handler_count2(void); + Use ``detachInterrupt(3)`` instead. - int count1 = 0; - int count2 = 0; +.. cpp:function:: void HardwareTimer::detachCompare4Interrupt() - void setup() - { - // Set up BUT for input - pinMode(BOARD_BUTTON_PIN, INPUT_PULLUP); + Use ``detachInterrupt(4)`` instead. - // Setup Counting Timers - Timer3.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer4.setChannel1Mode(TIMER_OUTPUTCOMPARE); - Timer3.pause(); - Timer4.pause(); - Timer3.setCount(0); - Timer4.setCount(0); - Timer3.setOverflow(30000); - Timer4.setOverflow(30000); - Timer3.setCompare1(1000); // somewhere in the middle - Timer4.setCompare1(1000); - Timer3.attachCompare1Interrupt(handler1); - Timer4.attachCompare1Interrupt(handler2); - Timer3.resume(); - Timer4.resume(); - } +.. cpp:function:: void HardwareTimer::generateUpdate() - void loop() { - // Display the running counts - SerialUSB.print("Count 1: "); - SerialUSB.print(count1); - SerialUSB.print("\t\tCount 2: "); - SerialUSB.println(count2); - - // Run... while BUT is held, pause Count2 - for(int i = 0; i<1000; i++) { - if(digitalRead(BOARD_BUTTON_PIN)) { - Timer4.pause(); - } else { - Timer4.resume(); - } - delay(1); - } - } + Use ``refresh()`` instead. - void handler1(void) { - count1++; - } - void handler2(void) { - count2++; - } +In previous releases, to interact with a particular timers, you would +use one of the predefined ``HardwareTimer`` instances ``Timer1``, +``Timer2``, ``Timer3``, and ``Timer4``. These are still available for +now, but they are also deprecated, and will be removed in a future +release. As detailed in :ref:`lang-hardwaretimer-getting-started`, +you should define your own ``HardwareTimer`` variables. diff --git a/docs/source/timers.rst b/docs/source/timers.rst index cb30081..9163e69 100644 --- a/docs/source/timers.rst +++ b/docs/source/timers.rst @@ -45,6 +45,16 @@ event" interrupt is generated. You can configure the Maple to notify you when this takes place, by registering an interrupt handler, which is a function that will be called when the update event occurs. +By default, different compare values only change the relative offsets +between events on a single timer ("phase"). They don't control the +frequency with which they occur. However, a common trick is to +increment the compare value manually in the interrupt handler so that +the event will fire again after the increment period. There can be a +different increment value for each channel, so this trick allows +events to be programmed at 4 different rates on a single timer. Note +that function call overheads mean that the smallest increment rate is +at least a few microseconds. + Function Reference ------------------ diff --git a/wirish/HardwareTimer.cpp b/wirish/HardwareTimer.cpp index 04d1c76..d0e32c3 100644 --- a/wirish/HardwareTimer.cpp +++ b/wirish/HardwareTimer.cpp @@ -22,204 +22,125 @@ * THE SOFTWARE. *****************************************************************************/ -/* - * wirish timer class to manage the four 16-bit timer peripherals - */ - -#include "wirish.h" #include "HardwareTimer.h" +#include "boards.h" // for CYCLES_PER_MICROSECOND +#include "wirish_math.h" -HardwareTimer::HardwareTimer(timer_dev_num timerNum) { - ASSERT(timerNum != TIMER_INVALID); +// TODO [0.1.0] Remove deprecated pieces - this->timerNum = timerNum; -} +#ifdef STM32_MEDIUM_DENSITY +#define NR_TIMERS 4 +#elif defined(STM32_HIGH_DENSITY) +#define NR_TIMERS 8 +#else +#error "Unsupported density" +#endif -void HardwareTimer::resume(void) { - timer_resume(this->timerNum); +#define MAX_RELOAD ((1 << 16) - 1) + +HardwareTimer::HardwareTimer(uint8 timerNum) { + if (timerNum > NR_TIMERS) { + ASSERT(0); + } + timer_dev *devs[] = { + TIMER1, + TIMER2, + TIMER3, + TIMER4, +#ifdef STM32_HIGH_DENSITY + TIMER5, + TIMER6, + TIMER7, + TIMER8, +#endif + }; + this->dev = devs[timerNum - 1]; } void HardwareTimer::pause(void) { - timer_pause(this->timerNum); + timer_pause(this->dev); } -uint16 HardwareTimer::getPrescaleFactor(void) { - return timer_get_prescaler(this->timerNum) + 1; +void HardwareTimer::resume(void) { + timer_resume(this->dev); +} + +uint32 HardwareTimer::getPrescaleFactor(void) { + return timer_get_prescaler(this->dev) + 1; } -void HardwareTimer::setPrescaleFactor(uint16 factor) { - // The prescaler register is zero-indexed - timer_set_prescaler(this->timerNum, factor-1); +void HardwareTimer::setPrescaleFactor(uint32 factor) { + timer_set_prescaler(this->dev, (uint16)(factor - 1)); } uint16 HardwareTimer::getOverflow() { - return timer_get_reload(this->timerNum); + return timer_get_reload(this->dev); } void HardwareTimer::setOverflow(uint16 val) { - timer_set_reload(this->timerNum, val); + timer_set_reload(this->dev, val); } uint16 HardwareTimer::getCount(void) { - return timer_get_count(this->timerNum); + return timer_get_count(this->dev); } void HardwareTimer::setCount(uint16 val) { uint16 ovf = this->getOverflow(); - timer_set_count(this->timerNum, min(val, ovf)); + timer_set_count(this->dev, min(val, ovf)); } +// FIXME [0.0.10 beta] test! uint16 HardwareTimer::setPeriod(uint32 microseconds) { // Not the best way to handle this edge case? - if(!microseconds) { - setPrescaleFactor(1); - setOverflow(1); + if (!microseconds) { + this->setPrescaleFactor(1); + this->setOverflow(1); return this->getOverflow(); } - uint32 cycles = microseconds * CYCLES_PER_MICROSECOND; - - // With a prescale factor of 1, there are CYCLES_PER_MICROSECOND - // counts/ms - uint16 ps = (uint16)((cycles >> 16) + 1); - setPrescaleFactor(ps); - - // Finally, this overflow will always be less than 65536 - setOverflow((cycles/ps) - 1); - - return this->getOverflow(); -} -void HardwareTimer::setChannelMode(int channel, TimerMode mode) { - timer_set_mode(this->timerNum, channel, mode); + uint32 period_cyc = microseconds * CYCLES_PER_MICROSECOND; + uint16 prescaler = (uint16)(period_cyc / MAX_RELOAD); + uint16 overflow = (uint16)round(period_cyc / prescaler); + this->setPrescaleFactor(prescaler); + this->setOverflow(overflow); + return overflow; } -void HardwareTimer::setChannel1Mode(TimerMode mode) { - this->setChannelMode(1, mode); -} - -void HardwareTimer::setChannel2Mode(TimerMode mode) { - this->setChannelMode(2, mode); -} - -void HardwareTimer::setChannel3Mode(TimerMode mode) { - this->setChannelMode(3, mode); -} - -void HardwareTimer::setChannel4Mode(TimerMode mode) { - this->setChannelMode(4, mode); +void HardwareTimer::setMode(int channel, timer_mode mode) { + timer_set_mode(this->dev, (uint8)channel, (timer_mode)mode); } uint16 HardwareTimer::getCompare(int channel) { - return timer_get_compare_value(this->timerNum, channel); -} - -uint16 HardwareTimer::getCompare1() { - return this->getCompare(1); -} - -uint16 HardwareTimer::getCompare2() { - return this->getCompare(2); -} - -uint16 HardwareTimer::getCompare3() { - return this->getCompare(3); -} - -uint16 HardwareTimer::getCompare4() { - return this->getCompare(4); + return timer_get_compare(this->dev, (uint8)channel); } void HardwareTimer::setCompare(int channel, uint16 val) { uint16 ovf = this->getOverflow(); - timer_set_compare_value(this->timerNum, channel, min(val, ovf)); -} - -void HardwareTimer::setCompare1(uint16 val) { - this->setCompare(1, val); -} - -void HardwareTimer::setCompare2(uint16 val) { - this->setCompare(2, val); -} - -void HardwareTimer::setCompare3(uint16 val) { - this->setCompare(3, val); -} - -void HardwareTimer::setCompare4(uint16 val) { - this->setCompare(4, val); + timer_set_compare(this->dev, (uint8)channel, min(val, ovf)); } void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) { - timer_attach_interrupt(this->timerNum, channel, handler); -} - -void HardwareTimer::attachCompare1Interrupt(voidFuncPtr handler) { - this->attachInterrupt(1, handler); -} - -void HardwareTimer::attachCompare2Interrupt(voidFuncPtr handler) { - this->attachInterrupt(2, handler); -} - -void HardwareTimer::attachCompare3Interrupt(voidFuncPtr handler) { - this->attachInterrupt(3, handler); -} - -void HardwareTimer::attachCompare4Interrupt(voidFuncPtr handler) { - this->attachInterrupt(4, handler); + timer_attach_interrupt(this->dev, (uint8)channel, handler); } void HardwareTimer::detachInterrupt(int channel) { - timer_detach_interrupt(this->timerNum, channel); -} - -void HardwareTimer::detachCompare1Interrupt(void) { - this->detachInterrupt(1); -} - -void HardwareTimer::detachCompare2Interrupt(void) { - this->detachInterrupt(2); -} - -void HardwareTimer::detachCompare3Interrupt(void) { - this->detachInterrupt(3); + timer_detach_interrupt(this->dev, (uint8)channel); } -void HardwareTimer::detachCompare4Interrupt(void) { - this->detachInterrupt(4); +void HardwareTimer::refresh(void) { + timer_generate_update(this->dev); } -void HardwareTimer::generateUpdate(void) { - timer_generate_update(this->timerNum); -} +/* -- Deprecated predefined instances -------------------------------------- */ -HardwareTimer Timer1(TIMER1); -HardwareTimer Timer2(TIMER2); -HardwareTimer Timer3(TIMER3); -HardwareTimer Timer4(TIMER4); +HardwareTimer Timer1(1); +HardwareTimer Timer2(2); +HardwareTimer Timer3(3); +HardwareTimer Timer4(4); #ifdef STM32_HIGH_DENSITY -HardwareTimer Timer5(TIMER5); // High-density devices only -HardwareTimer Timer8(TIMER8); // High-density devices only +HardwareTimer Timer5(5); +HardwareTimer Timer6(6); +HardwareTimer Timer7(7); +HardwareTimer Timer8(8); #endif - -HardwareTimer* getTimer(timer_dev_num timerNum) { - switch (timerNum) { - case TIMER1: - return &Timer1; - case TIMER2: - return &Timer2; - case TIMER3: - return &Timer3; - case TIMER4: - return &Timer4; -#ifdef STM32_HIGH_DENSITY - case TIMER5: - return &Timer5; - case TIMER8: - return &Timer8; -#endif - default: - return 0; - } -} diff --git a/wirish/HardwareTimer.h b/wirish/HardwareTimer.h index 4030adc..fd8ca9a 100644 --- a/wirish/HardwareTimer.h +++ b/wirish/HardwareTimer.h @@ -23,66 +23,45 @@ *****************************************************************************/ /** - * @brief wirish timer class to manage the four 16-bit timer peripherals + * @brief Wirish timer class. */ #ifndef _HARDWARETIMER_H_ #define _HARDWARETIMER_H_ -#include "timers.h" +// TODO [0.1.0] Remove deprecated pieces, pick a better API + +#include "timer.h" + +/** Timer mode. */ +typedef timer_mode TimerMode; + +/** @brief Deprecated; use TIMER_OUTPUT_COMPARE instead. */ +#define TIMER_OUTPUTCOMPARE TIMER_OUTPUT_COMPARE /** - * Interface to one of the 16-bit timer peripherals. - * - * User code should not instantiate this class directly; instead, use - * one of the predefined Timer instances (Timer1, Timer2, etc.). - * - * HardwareTimer instances can be configured to generate periodic or - * delayed events with minimal work done by the microcontroller. Each - * timer maintains a single 16-bit count that can be configured with a - * prescaler and overflow value. - * - * By default, a timer's counter is incremented once per clock cycle. - * The prescaler acts as a divider of the 72MHz Maple system clock; - * without prescaling, the timer's count would reach 65535 (2**16-1) - * and roll over over 1000 times per second. - * - * The overflow value is the maximum value the counter will reach. It - * defaults to 65535; smaller values will cause the counter to reset - * more frequently. + * @brief Interface to one of the 16-bit timer peripherals. */ class HardwareTimer { - private: - timer_dev_num timerNum; - - public: - HardwareTimer(timer_dev_num timer_num); +private: + timer_dev *dev; +public: /** - * Return this timer's device number. For example, - * Timer1.getTimerNum() == TIMER1 + * @brief Construct a new HardwareTimer instance. + * @param timerNum number of the timer to control. */ - timer_dev_num getTimerNum() { return timerNum; } + HardwareTimer(uint8 timerNum); /** - * Stop the counter, without affecting its configuration. - * - * The timer will no longer count or fire interrupts after this - * function is called, until it is resumed. This function is - * useful during timer setup periods, in order to prevent - * interrupts from firing before the timer is fully configured. - * - * Note that there is some function call overhead associated with - * this method, so using it in concert with - * HardwareTimer::resume() is not a robust way to align multiple - * timers to the same count value. + * @brief Stop the counter, without affecting its configuration. * * @see HardwareTimer::resume() */ void pause(void); /** - * Resume a paused timer, without affecting its configuration. + * @brief Resume a paused timer, without affecting its configuration. * * The timer will resume counting and firing interrupts as * appropriate. @@ -97,66 +76,51 @@ class HardwareTimer { void resume(void); /** - * Returns the timer's prescale factor. + * @brief Get the timer's prescale factor. + * @return Timer prescaler, from 1 to 65,536. * @see HardwareTimer::setPrescaleFactor() */ - uint16 getPrescaleFactor(); + uint32 getPrescaleFactor(); /** - * Set the timer's prescale factor. + * @brief Set the timer's prescale factor. * - * The prescaler acts as a clock divider to slow down the rate at - * which the counter increments. + * The new value won't take effect until the next time the counter + * overflows. You can force the counter to reset using + * HardwareTimer::refresh(). * - * For example, the system clock rate is 72MHz, so the counter - * will reach 65535 in (13.89 nanoseconds) * (65535 counts) = - * (910.22 microseconds), or about a thousand times a second. If - * the prescaler equals 1098, then the clock rate is effectively - * 65.56KHz, and the counter will reach 65536 in (15.25 - * microseconds) * (65536 counts) = (0.999 seconds), or about once - * per second. - * - * The HardwareTimer::setPeriod() method may also be used as a - * convenient alternative. - * - * @param factor The new prescale value to set. - * @see HardwareTimer::setPeriod() + * @param factor The new prescale value to set, from 1 to 65,536. + * @see HardwareTimer::refresh() */ - void setPrescaleFactor(uint16 factor); + void setPrescaleFactor(uint32 factor); /** - * Gets the timer overflow value. + * @brief Get the timer overflow value. * @see HardwareTimer::setOverflow() */ uint16 getOverflow(); /** - * Sets the timer overflow (or "reload") value. + * @brief Set the timer overflow (or "reload") value. * - * When the timer's counter reaches this, value it resets to - * zero. Its default value is 65535 (the largest unsigned 16-bit - * integer); setting the overflow to anything lower will cause - * interrupts to be called more frequently (see the setPeriod() - * function below for a shortcut). This number sets the maximum - * value for the channel compare values. + * The new value won't take effect until the next time the counter + * overflows. You can force the counter to reset using + * HardwareTimer::refresh(). * * @param val The new overflow value to set + * @see HardwareTimer::refresh() */ void setOverflow(uint16 val); /** - * Retrieve the current timer count. + * @brief Get the current timer count. * * @return The timer's current count value */ uint16 getCount(void); /** - * Set the current timer count. - * - * Note that there is some function call overhead associated with - * calling this method, so using it is not a robust way to get - * multiple timers to share a count value. + * @brief Set the current timer count. * * @param val The new count value to set. If this value exceeds * the timer's overflow value, it is truncated to the @@ -165,143 +129,50 @@ class HardwareTimer { void setCount(uint16 val); /** - * Configure the prescaler and overflow values to generate a timer + * @brief Set the timer's period in microseconds. + * + * Configures the prescaler and overflow values to generate a timer * reload with a period as close to the given number of * microseconds as possible. * - * The return value is the overflow, which may be used to set - * channel compare values. However, if a clock that fires an - * interrupt every given number of microseconds is all that is - * desired, and the relative "phases" are unimportant, channel - * compare values may all be set to 1. - * - * @param microseconds the desired period of the timer. - * @return the overflow value (and thus, the largest value that can be - * set as a compare). + * @param microseconds The desired period of the timer. This must be + * greater than zero. + * @return The new overflow value. */ uint16 setPeriod(uint32 microseconds); /** - * Set the given channel of this timer to the given mode. - * + * @brief Configure a timer channel's mode. * @param channel Timer channel, from 1 to 4 * @param mode Mode to set */ - void setChannelMode(int channel, TimerMode mode); - - /** - * Set channel 1 of this timer to the given mode. - * - * Note: Timer1.setChannel1Mode(TIMER_PWM) may not work as - * expected; if you want PWM functionality on a channel make sure - * you don't set it to something else! - * - * @see TimerMode - */ - void setChannel1Mode(TimerMode mode); - - /** - * Set channel 2 of this timer to the given mode. - * @see TimerMode - */ - void setChannel2Mode(TimerMode mode); - - /** - * Set channel 3 of this timer to the given mode. - * @see TimerMode - */ - void setChannel3Mode(TimerMode mode); - - /** - * Set channel 4 of this timer to the given mode. - * @see TimerMode - */ - void setChannel4Mode(TimerMode mode); + void setMode(int channel, timer_mode mode); /** - * Gets the compare value for the given channel. + * @brief Get the compare value for the given channel. * @see HardwareTimer::setCompare() */ uint16 getCompare(int channel); - /** Equivalent to getCompare(1) */ - uint16 getCompare1(); - - /** Equivalent to getCompare(2) */ - uint16 getCompare2(); - - /** Equivalent to getCompare(3) */ - uint16 getCompare3(); - - /** Equivalent to getCompare(4) */ - uint16 getCompare4(); - /** - * Sets the compare value for the given channel. - * - * When the counter reaches this value the interrupt for this - * channel will fire if the channel mode is TIMER_OUTPUTCOMPARE - * and an interrupt is attached. - * - * By default, this only changes the relative offsets between - * events on a single timer ("phase"); they don't control the - * frequency with which they occur. However, a common trick is to - * increment the compare value manually in the interrupt handler - * so that the event will fire again after the increment - * period. There can be a different increment value for each - * channel, so this trick allows events to be programmed at 4 - * different rates on a single timer. Note that function call - * overheads mean that the smallest increment rate is at least a - * few microseconds. + * @brief Set the compare value for the given channel. * * @param channel the channel whose compare to set, from 1 to 4. * @param compare The compare value to set. If greater than this * timer's overflow value, it will be truncated to * the overflow value. * - * @see TimerMode - * @see HardwareTimer::setChannelMode() + * @see timer_mode + * @see HardwareTimer::setMode() * @see HardwareTimer::attachInterrupt() */ void setCompare(int channel, uint16 compare); /** - * Equivalent to setCompare(1, compare). - */ - void setCompare1(uint16 compare); - - /** - * Equivalent to setCompare(2, compare). - */ - void setCompare2(uint16 compare); - - /** - * Equivalent to setCompare(3, compare). - */ - void setCompare3(uint16 compare); - - /** - * Equivalent to setCompare(4, compare). - */ - void setCompare4(uint16 compare); - - /** - * Attach an interrupt handler to the given channel. This - * interrupt handler will be called when the timer's counter - * reaches the given channel compare value. - * - * The argument should be a function which takes no arguments and - * has no return value; i.e. it should have signature + * @brief Attach an interrupt handler to the given channel. * - * void (*handler)(void); - * - * Note: The function (often called an interrupt service routine, - * or ISR) should attempt to return as quickly as possible. - * Blinking the LED, some logic, PWM updates, and Serial writes - * are fine; writing to SerialUSB or waiting for user input can - * take a long time and other compare interrupts won't fire. Tip: - * if you have a delay() in your interrupt routine, you're probably - * doing it wrong. + * This interrupt handler will be called when the timer's counter + * reaches the given channel compare value. * * @param channel the channel to attach the ISR to, from 1 to 4. * @param handler The ISR to attach to the given channel. @@ -310,32 +181,10 @@ class HardwareTimer { void attachInterrupt(int channel, voidFuncPtr handler); /** - * Equivalent to attachCompareInterrupt(1, handler). - * @see HardwareTimer::attachCompareInterrupt() - */ - void attachCompare1Interrupt(voidFuncPtr handler); - - /** - * Equivalent to attachCompareInterrupt(2, handler). - * @see HardwareTimer::attachCompareInterrupt() - */ - void attachCompare2Interrupt(voidFuncPtr handler); - - /** - * Equivalent to attachCompareInterrupt(3, handler). - * @see HardwareTimer::attachCompareInterrupt() - */ - void attachCompare3Interrupt(voidFuncPtr handler); - - /** - * Equivalent to attachCompareInterrupt(4, handler). - * @see HardwareTimer::attachCompareInterrupt() - */ - void attachCompare4Interrupt(voidFuncPtr handler); - - /** - * Remove the interrupt handler attached to the given channel, if - * any. The handler will no longer be called by this timer. + * @brief Remove the interrupt handler attached to the given + * channel, if any. + * + * The handler will no longer be called by this timer. * * @param channel the channel whose interrupt to detach, from 1 to 4. * @see HardwareTimer::attachInterrupt() @@ -343,71 +192,138 @@ class HardwareTimer { void detachInterrupt(int channel); /** - * Equivalent to detachInterrupt(1). - * @see HardwareTimer::detachInterrupt() + * @brief Reset the counter, and update the prescaler and overflow + * values. + * + * This will reset the counter to 0 in upcounting mode (the + * default). It will also update the timer's prescaler and + * overflow, if you have set them up to be changed using + * HardwareTimer::setPrescaleFactor() or + * HardwareTimer::setOverflow(). + * + * @see HardwareTimer::setPrescaleFactor() + * @see HardwareTimer::setOverflow() */ - void detachCompare1Interrupt(void); + void refresh(void); - /** - * Equivalent to detachInterrupt(2). - * @see HardwareTimer::detachInterrupt() - */ - void detachCompare2Interrupt(void); + /* -- Deprecated methods ----------------------------------------------- */ - /** - * Equivalent to detachInterrupt(3). - * @see HardwareTimer::detachInterrupt() - */ - void detachCompare3Interrupt(void); + /** @brief Deprecated; use setMode(channel, mode) instead. */ + void setChannelMode(int channel, timer_mode mode) { + setMode(channel, mode); + } - /** - * Equivalent to detachInterrupt(4). - * @see HardwareTimer::detachInterrupt() - */ - void detachCompare4Interrupt(void); + /** @brief Deprecated; use setMode(TIMER_CH1, mode) instead. */ + void setChannel1Mode(timer_mode mode) { setMode(TIMER_CH1, mode); } - /** - * Re-initializes the counter (to 0 in upcounting mode, which is - * the default), and generates an update of the prescale and - * overflow registers. - */ - void generateUpdate(void); + /** @brief Deprecated; use setMode(TIMER_CH2, mode) instead. */ + void setChannel2Mode(timer_mode mode) { setMode(TIMER_CH2, mode); } + + /** @brief Deprecated; use setMode(TIMER_CH3, mode) instead. */ + void setChannel3Mode(timer_mode mode) { setMode(TIMER_CH3, mode); } + + /** @brief Deprecated; use setMode(TIMER_CH4, mode) instead. */ + void setChannel4Mode(timer_mode mode) { setMode(TIMER_CH4, mode); } + + /** @brief Deprecated; use return getCompare(TIMER_CH1) instead. */ + uint16 getCompare1() { return getCompare(TIMER_CH1); } + + /** @brief Deprecated; use return getCompare(TIMER_CH2) instead. */ + uint16 getCompare2() { return getCompare(TIMER_CH2); } + + /** @brief Deprecated; use return getCompare(TIMER_CH3) instead. */ + uint16 getCompare3() { return getCompare(TIMER_CH3); } + + /** @brief Deprecated; use return getCompare(TIMER_CH4) instead. */ + uint16 getCompare4() { return getCompare(TIMER_CH4); } + + /** @brief Deprecated; use setCompare(TIMER_CH1, compare) instead. */ + void setCompare1(uint16 compare) { setCompare(TIMER_CH1, compare); } + + /** @brief Deprecated; use setCompare(TIMER_CH2, compare) instead. */ + void setCompare2(uint16 compare) { setCompare(TIMER_CH2, compare); } + + /** @brief Deprecated; use setCompare(TIMER_CH3, compare) instead. */ + void setCompare3(uint16 compare) { setCompare(TIMER_CH3, compare); } + + /** @brief Deprecated; use setCompare(TIMER_CH4, compare) instead. */ + void setCompare4(uint16 compare) { setCompare(TIMER_CH4, compare); } + + /** @brief Deprecated; use attachInterrupt(TIMER_CH1, handler) instead. */ + void attachCompare1Interrupt(voidFuncPtr handler) { + attachInterrupt(TIMER_CH1, handler); + } + + /** @brief Deprecated; use attachInterrupt(TIMER_CH2, handler) instead. */ + void attachCompare2Interrupt(voidFuncPtr handler) { + attachInterrupt(TIMER_CH2, handler); + } + + /** @brief Deprecated; use attachInterrupt(TIMER_CH3, handler) instead. */ + void attachCompare3Interrupt(voidFuncPtr handler) { + attachInterrupt(TIMER_CH3, handler); + } + + /** @brief Deprecated; use attachInterrupt(TIMER_CH4, handler) instead. */ + void attachCompare4Interrupt(voidFuncPtr handler) { + attachInterrupt(TIMER_CH4, handler); + } + + /** @brief Deprecated; use detachInterrupt(TIMER_CH1) instead. */ + void detachCompare1Interrupt(void) { detachInterrupt(TIMER_CH1); } + + /** @brief Deprecated; use detachInterrupt(TIMER_CH2) instead. */ + void detachCompare2Interrupt(void) { detachInterrupt(TIMER_CH2); } + + /** @brief Deprecated; use detachInterrupt(TIMER_CH3) instead. */ + void detachCompare3Interrupt(void) { detachInterrupt(TIMER_CH3); } + + /** @brief Deprecated; use detachInterrupt(TIMER_CH4) instead. */ + void detachCompare4Interrupt(void) { detachInterrupt(TIMER_CH4); } + + /** @brief Deprecated; use refresh() instead. */ + void generateUpdate(void) { refresh(); } }; -/** Pre-instantiated timer for use by user code. */ +/* -- The rest of this file is deprecated. --------------------------------- */ + +/** + * @brief Deprecated. + * + * Pre-instantiated timer. + */ extern HardwareTimer Timer1; -/** Pre-instantiated timer for use by user code. */ +/** + * @brief Deprecated. + * + * Pre-instantiated timer. + */ extern HardwareTimer Timer2; -/** Pre-instantiated timer for use by user code. */ +/** + * @brief Deprecated. + * + * Pre-instantiated timer. + */ extern HardwareTimer Timer3; -/** Pre-instantiated timer for use by user code. */ +/** + * @brief Deprecated. + * + * Pre-instantiated timer. + */ extern HardwareTimer Timer4; #ifdef STM32_HIGH_DENSITY -/** Pre-instantiated timer for use by user code, on devices with - more than four timers (this does not include the Maple). */ -extern HardwareTimer Timer5; -/** Pre-instantiated timer for use by user code, on devices with - more than four timers (this does not include the Maple). */ -extern HardwareTimer Timer8; -#endif - /** - * Get one of the pre-instantiated HardwareTimer instances, given a - * timer device number. - * - * Be careful not to pass an actual number to this function. For - * example, getTimer(1) will not return Timer1. Use a real - * timer_dev_num, e.g. TIMER1, TIMER2, etc. + * @brief Deprecated. * - * @param timerNum the timer device number, e.g. TIMER1. - * - * @return Pointer to the HardwareTimer instance corresponding to the - * given timer device number. If timerNum is TIMER_INVALID, returns a - * null pointer. + * Pre-instantiated timer. + */ +extern HardwareTimer Timer5; +/** + * @brief Deprecated. * - * @see timer_dev_num + * Pre-instantiated timer. */ -HardwareTimer* getTimer(timer_dev_num timerNum); - +extern HardwareTimer Timer8; #endif +#endif diff --git a/wirish/rules.mk b/wirish/rules.mk index c3608e3..6999288 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -23,6 +23,7 @@ cppSRCS_$(d) := wirish_math.cpp \ boards/maple_RET6.cpp \ comm/HardwareSerial.cpp \ comm/HardwareSPI.cpp \ + HardwareTimer.cpp \ usb_serial.cpp \ cxxabi-compat.cpp \ wirish_shift.cpp \ diff --git a/wirish/wirish.h b/wirish/wirish.h index d30ad20..82a9897 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -44,6 +44,7 @@ #include "wirish_time.h" #include "HardwareSPI.h" #include "HardwareSerial.h" +#include "HardwareTimer.h" #include "usb_serial.h" /* Arduino wiring macros and bit defines */ -- cgit v1.2.3