Updated to the new locm3 changed to stdint types.

This commit is contained in:
Piotr Esden-Tempski
2013-06-12 19:43:10 -07:00
parent adddf9e418
commit cb73d4ba3d
71 changed files with 443 additions and 443 deletions

View File

@@ -59,7 +59,7 @@ enum {
PLL_DIV_16MHZ = 25, PLL_DIV_16MHZ = 25,
}; };
static const u8 plldiv[] = { static const uint8_t plldiv[] = {
PLL_DIV_80MHZ, PLL_DIV_80MHZ,
PLL_DIV_57MHZ, PLL_DIV_57MHZ,
PLL_DIV_40MHZ, PLL_DIV_40MHZ,
@@ -93,7 +93,7 @@ static void gpio_setup(void)
* This port is used to control the RGB LED * This port is used to control the RGB LED
*/ */
periph_clock_enable(RCC_GPIOF); periph_clock_enable(RCC_GPIOF);
const u32 outpins = (LED_R | LED_G | LED_B); const uint32_t outpins = (LED_R | LED_G | LED_B);
gpio_mode_setup(RGB_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, outpins); gpio_mode_setup(RGB_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, outpins);
gpio_set_output_config(RGB_PORT, GPIO_OTYPE_PP, GPIO_DRIVE_2MA, outpins); gpio_set_output_config(RGB_PORT, GPIO_OTYPE_PP, GPIO_DRIVE_2MA, outpins);
@@ -101,7 +101,7 @@ static void gpio_setup(void)
/* /*
* Now take care of our buttons * Now take care of our buttons
*/ */
const u32 btnpins = USR_SW1 | USR_SW2; const uint32_t btnpins = USR_SW1 | USR_SW2;
/* /*
* PF0 is a locked by default. We need to unlock it before we can * PF0 is a locked by default. We need to unlock it before we can
@@ -118,7 +118,7 @@ static void gpio_setup(void)
*/ */
static void irq_setup(void) static void irq_setup(void)
{ {
const u32 btnpins = USR_SW1 | USR_SW2; const uint32_t btnpins = USR_SW1 | USR_SW2;
/* Trigger interrupt on rising-edge (when button is depressed) */ /* Trigger interrupt on rising-edge (when button is depressed) */
gpio_configure_trigger(GPIOF, GPIO_TRIG_EDGE_RISE, btnpins); gpio_configure_trigger(GPIOF, GPIO_TRIG_EDGE_RISE, btnpins);
/* Finally, Enable interrupt */ /* Finally, Enable interrupt */

View File

@@ -61,8 +61,8 @@ static void uart_irq_setup(void)
*/ */
void uart0_isr(void) void uart0_isr(void)
{ {
u8 rx; uint8_t rx;
u32 irq_clear = 0; uint32_t irq_clear = 0;
if (uart_is_interrupt_source(UART0, UART_INT_RX)) { if (uart_is_interrupt_source(UART0, UART_INT_RX)) {
rx = uart_recv(UART0); rx = uart_recv(UART0);

View File

@@ -49,7 +49,7 @@ static void uart_setup(void)
int main(void) int main(void)
{ {
u8 rx; uint8_t rx;
gpio_enable_ahb_aperture(); gpio_enable_ahb_aperture();
uart_setup(); uart_setup();

View File

@@ -52,7 +52,7 @@ static void gpio_setup(void)
GPIO3_DIR |= PIN_EN1V8; /* GPIO3[6] on P6_10 as output. */ GPIO3_DIR |= PIN_EN1V8; /* GPIO3[6] on P6_10 as output. */
} }
u32 boot0, boot1, boot2, boot3; uint32_t boot0, boot1, boot2, boot3;
int main(void) int main(void)
{ {

View File

@@ -52,7 +52,7 @@ static void gpio_setup(void)
GPIO3_DIR |= PIN_EN1V8; /* GPIO3[6] on P6_10 as output. */ GPIO3_DIR |= PIN_EN1V8; /* GPIO3[6] on P6_10 as output. */
} }
u32 boot0, boot1, boot2, boot3; uint32_t boot0, boot1, boot2, boot3;
int main(void) int main(void)
{ {

View File

@@ -62,9 +62,9 @@ static void gpio_setup(void)
int main(void) int main(void)
{ {
int i; int i;
u8 ssp_val; uint8_t ssp_val;
u8 serial_clock_rate; uint8_t serial_clock_rate;
u8 clock_prescale_rate; uint8_t clock_prescale_rate;
gpio_setup(); gpio_setup();
@@ -86,7 +86,7 @@ int main(void)
while (1) { while (1) {
ssp_write(SSP1_NUM, (u16)ssp_val); ssp_write(SSP1_NUM, (uint16_t)ssp_val);
gpio_set(GPIO2, GPIOPIN1); /* LED on */ gpio_set(GPIO2, GPIOPIN1); /* LED on */

View File

@@ -27,8 +27,8 @@
#include "../jellybean_conf.h" #include "../jellybean_conf.h"
/* Global counter incremented by SysTick Interrupt each millisecond */ /* Global counter incremented by SysTick Interrupt each millisecond */
volatile u32 g_ulSysTickCount; volatile uint32_t g_ulSysTickCount;
u32 g_NbCyclePerSecond; uint32_t g_NbCyclePerSecond;
static void gpio_setup(void) static void gpio_setup(void)
{ {
@@ -67,7 +67,7 @@ static void gpio_setup(void)
static void systick_setup(void) static void systick_setup(void)
{ {
u32 systick_reload_val; uint32_t systick_reload_val;
g_ulSysTickCount = 0; g_ulSysTickCount = 0;
/* Disable IRQ globally */ /* Disable IRQ globally */
@@ -106,15 +106,15 @@ static void scs_dwt_cycle_counter_enabled(void)
SCS_DWT_CTRL |= SCS_DWT_CTRL_CYCCNTENA; SCS_DWT_CTRL |= SCS_DWT_CTRL_CYCCNTENA;
} }
static u32 sys_tick_get_time_ms(void) static uint32_t sys_tick_get_time_ms(void)
{ {
return g_ulSysTickCount; return g_ulSysTickCount;
} }
static u32 sys_tick_delta_time_ms(u32 start, u32 end) static uint32_t sys_tick_delta_time_ms(uint32_t start, uint32_t end)
{ {
#define MAX_T_U32 ((2^32)-1) #define MAX_T_U32 ((2^32)-1)
u32 diff; uint32_t diff;
if(end > start) if(end > start)
{ {
@@ -127,10 +127,10 @@ static u32 sys_tick_delta_time_ms(u32 start, u32 end)
return diff; return diff;
} }
static void sys_tick_wait_time_ms(u32 wait_ms) static void sys_tick_wait_time_ms(uint32_t wait_ms)
{ {
u32 start, end; uint32_t start, end;
u32 tickms; uint32_t tickms;
start = sys_tick_get_time_ms(); start = sys_tick_get_time_ms();

View File

@@ -26,22 +26,22 @@
#include <libopencm3/stm32/can.h> #include <libopencm3/stm32/can.h>
struct can_tx_msg { struct can_tx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
}; };
struct can_rx_msg { struct can_rx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
u8 fmi; uint8_t fmi;
}; };
struct can_tx_msg can_tx_msg; struct can_tx_msg can_tx_msg;
@@ -166,7 +166,7 @@ static void can_setup(void)
void sys_tick_handler(void) void sys_tick_handler(void)
{ {
static int temp32 = 0; static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0}; static uint8_t data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 100ms = 1s /* We call this handler every 1ms so 100ms = 1s
* Resulting in 100Hz message frequency. * Resulting in 100Hz message frequency.
@@ -195,9 +195,9 @@ void sys_tick_handler(void)
void usb_lp_can_rx0_isr(void) void usb_lp_can_rx0_isr(void)
{ {
u32 id, fmi; uint32_t id, fmi;
bool ext, rtr; bool ext, rtr;
u8 length, data[8]; uint8_t length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data); can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);

View File

@@ -164,10 +164,10 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
(void)buf; (void)buf;
@@ -203,7 +203,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
return 0; return 0;
} }
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep) static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{ {
(void)ep; (void)ep;
@@ -219,7 +219,7 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
gpio_toggle(GPIOC, GPIO5); gpio_toggle(GPIOC, GPIO5);
} }
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue) static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;

View File

@@ -32,15 +32,15 @@
#define CMD_ERASE 0x41 #define CMD_ERASE 0x41
/* We need a special large control buffer for this device: */ /* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024]; uint8_t usbd_control_buffer[1024];
static enum dfu_state usbdfu_state = STATE_DFU_IDLE; static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static struct { static struct {
u8 buf[sizeof(usbd_control_buffer)]; uint8_t buf[sizeof(usbd_control_buffer)];
u16 len; uint16_t len;
u32 addr; uint32_t addr;
u16 blocknum; uint16_t blocknum;
} prog; } prog;
const struct usb_device_descriptor dev = { const struct usb_device_descriptor dev = {
@@ -113,7 +113,7 @@ static const char *usb_strings[] = {
"@Internal Flash /0x08000000/8*001Ka,56*001Kg", "@Internal Flash /0x08000000/8*001Ka,56*001Kg",
}; };
static u8 usbdfu_getstatus(u32 *bwPollTimeout) static uint8_t usbdfu_getstatus(uint32_t *bwPollTimeout)
{ {
switch (usbdfu_state) { switch (usbdfu_state) {
case STATE_DFU_DNLOAD_SYNC: case STATE_DFU_DNLOAD_SYNC:
@@ -142,20 +142,20 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
switch (prog.buf[0]) { switch (prog.buf[0]) {
case CMD_ERASE: case CMD_ERASE:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
flash_erase_page(*dat); flash_erase_page(*dat);
} }
case CMD_SETADDR: case CMD_SETADDR:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
prog.addr = *dat; prog.addr = *dat;
} }
} }
} else { } else {
u32 baseaddr = prog.addr + ((prog.blocknum - 2) * uint32_t baseaddr = prog.addr + ((prog.blocknum - 2) *
dfu_function.wTransferSize); dfu_function.wTransferSize);
for (i = 0; i < prog.len; i += 2) { for (i = 0; i < prog.len; i += 2) {
u16 *dat = (u16 *)(prog.buf + i); uint16_t *dat = (uint16_t *)(prog.buf + i);
flash_program_half_word(baseaddr + i, flash_program_half_word(baseaddr + i,
*dat); *dat);
} }
@@ -174,8 +174,8 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
} }
} }
static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)usbd_dev; (void)usbd_dev;
@@ -208,7 +208,7 @@ static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *
/* Upload not supported for now. */ /* Upload not supported for now. */
return 0; return 0;
case DFU_GETSTATUS: { case DFU_GETSTATUS: {
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout); (*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF; (*buf)[1] = bwPollTimeout & 0xFF;
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF; (*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
@@ -237,12 +237,12 @@ int main(void)
if (!gpio_get(GPIOA, GPIO10)) { if (!gpio_get(GPIOA, GPIO10)) {
/* Boot the application if it's valid. */ /* Boot the application if it's valid. */
if ((*(volatile u32 *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) { if ((*(volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address. */ /* Set vector table base address. */
SCB_VTOR = APP_ADDRESS & 0xFFFF; SCB_VTOR = APP_ADDRESS & 0xFFFF;
/* Initialise master stack pointer. */ /* Initialise master stack pointer. */
asm volatile("msr msp, %0"::"g" asm volatile("msr msp, %0"::"g"
(*(volatile u32 *)APP_ADDRESS)); (*(volatile uint32_t *)APP_ADDRESS));
/* Jump to application. */ /* Jump to application. */
(*(void (**)())(APP_ADDRESS + 4))(); (*(void (**)())(APP_ADDRESS + 4))();
} }

View File

@@ -57,7 +57,7 @@ const struct usb_device_descriptor dev_descr = {
}; };
/* I have no idea what this means. I haven't read the HID spec. */ /* I have no idea what this means. I haven't read the HID spec. */
static const u8 hid_report_descriptor[] = { static const uint8_t hid_report_descriptor[] = {
0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01, 0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03, 0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01, 0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
@@ -73,8 +73,8 @@ static const u8 hid_report_descriptor[] = {
static const struct { static const struct {
struct usb_hid_descriptor hid_descriptor; struct usb_hid_descriptor hid_descriptor;
struct { struct {
u8 bReportDescriptorType; uint8_t bReportDescriptorType;
u16 wDescriptorLength; uint16_t wDescriptorLength;
} __attribute__((packed)) hid_report; } __attribute__((packed)) hid_report;
} __attribute__((packed)) hid_function = { } __attribute__((packed)) hid_function = {
.hid_descriptor = { .hid_descriptor = {
@@ -176,9 +176,9 @@ static const char *usb_strings[] = {
}; };
/* Buffer used for control requests. */ /* Buffer used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *dev, struct usb_setup_data *req)) void (**complete)(usbd_device *dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
@@ -190,7 +190,7 @@ static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, u8
return 0; return 0;
/* Handle the HID report descriptor. */ /* Handle the HID report descriptor. */
*buf = (u8 *)hid_report_descriptor; *buf = (uint8_t *)hid_report_descriptor;
*len = sizeof(hid_report_descriptor); *len = sizeof(hid_report_descriptor);
return 1; return 1;
@@ -209,7 +209,7 @@ static void dfu_detach_complete(usbd_device *dev, struct usb_setup_data *req)
scb_reset_core(); scb_reset_core();
} }
static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *dev, struct usb_setup_data *req)) void (**complete)(usbd_device *dev, struct usb_setup_data *req))
{ {
(void)buf; (void)buf;
@@ -225,7 +225,7 @@ static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, u8
} }
#endif #endif
static void hid_set_config(usbd_device *dev, u16 wValue) static void hid_set_config(usbd_device *dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;
@@ -251,7 +251,7 @@ static void hid_set_config(usbd_device *dev, u16 wValue)
systick_counter_enable(); systick_counter_enable();
} }
static u8 spi_readwrite(u32 spi, u8 data) static uint8_t spi_readwrite(uint32_t spi, uint8_t data)
{ {
while (SPI_SR(spi) & SPI_SR_BSY) while (SPI_SR(spi) & SPI_SR_BSY)
; ;
@@ -261,9 +261,9 @@ static u8 spi_readwrite(u32 spi, u8 data)
return SPI_DR(spi); return SPI_DR(spi);
} }
static u8 accel_read(u8 addr) static uint8_t accel_read(uint8_t addr)
{ {
u8 ret; uint8_t ret;
gpio_clear(GPIOB, GPIO12); gpio_clear(GPIOB, GPIO12);
spi_readwrite(SPI2, addr | 0x80); spi_readwrite(SPI2, addr | 0x80);
ret = spi_readwrite(SPI2, 0); ret = spi_readwrite(SPI2, 0);
@@ -271,7 +271,7 @@ static u8 accel_read(u8 addr)
return ret; return ret;
} }
static void accel_write(u8 addr, u8 data) static void accel_write(uint8_t addr, uint8_t data)
{ {
gpio_clear(GPIOB, GPIO12); gpio_clear(GPIOB, GPIO12);
spi_readwrite(SPI2, addr); spi_readwrite(SPI2, addr);
@@ -279,7 +279,7 @@ static void accel_write(u8 addr, u8 data)
gpio_set(GPIOB, GPIO12); gpio_set(GPIOB, GPIO12);
} }
static void accel_get(s16 *x, s16 *y, s16 *z) static void accel_get(int16_t *x, int16_t *y, int16_t *z)
{ {
if (x) if (x)
*x = accel_read(ADXL345_DATAX0) | *x = accel_read(ADXL345_DATAX0) |
@@ -361,8 +361,8 @@ int main(void)
void sys_tick_handler(void) void sys_tick_handler(void)
{ {
s16 x, y; int16_t x, y;
u8 buf[4] = {0, 0, 0, 0}; uint8_t buf[4] = {0, 0, 0, 0};
accel_get(&x, &y, NULL); accel_get(&x, &y, NULL);
buf[1] = x >> 9; buf[1] = x >> 9;

View File

@@ -94,10 +94,10 @@ static void adc_setup(void)
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {
@@ -119,8 +119,8 @@ static void my_usart_print_int(u32 usart, int value)
int main(void) int main(void)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
u16 temperature = 0; uint16_t temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz(); rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -120,10 +120,10 @@ static void adc_setup(void)
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0);
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {
@@ -145,8 +145,8 @@ static void my_usart_print_int(u32 usart, int value)
int main(void) int main(void)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
u16 temperature = 0; uint16_t temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz(); rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -27,7 +27,7 @@
#include <libopencm3/stm32/timer.h> #include <libopencm3/stm32/timer.h>
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
volatile u16 temperature = 0; volatile uint16_t temperature = 0;
static void usart_setup(void) static void usart_setup(void)
{ {
@@ -132,10 +132,10 @@ static void adc_setup(void)
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0);
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {
@@ -157,7 +157,7 @@ static void my_usart_print_int(u32 usart, int value)
int main(void) int main(void)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
rcc_clock_setup_in_hse_12mhz_out_72mhz(); rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -27,11 +27,11 @@
#include <libopencm3/stm32/timer.h> #include <libopencm3/stm32/timer.h>
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
volatile u16 temperature = 0; volatile uint16_t temperature = 0;
volatile u16 v_refint = 0; volatile uint16_t v_refint = 0;
volatile u16 lisam_adc1 = 0; volatile uint16_t lisam_adc1 = 0;
volatile u16 lisam_adc2 = 0; volatile uint16_t lisam_adc2 = 0;
u8 channel_array[4]; /* for injected sampling, 4 channels max, for regular, 16 max */ uint8_t channel_array[4]; /* for injected sampling, 4 channels max, for regular, 16 max */
static void usart_setup(void) static void usart_setup(void)
{ {
@@ -149,10 +149,10 @@ static void adc_setup(void)
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {

View File

@@ -88,10 +88,10 @@ static void adc_setup(void)
adc_calibration(ADC1); adc_calibration(ADC1);
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {
@@ -113,8 +113,8 @@ static void my_usart_print_int(u32 usart, int value)
int main(void) int main(void)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
u16 temperature = 0; uint16_t temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz(); rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -26,22 +26,22 @@
#include <libopencm3/stm32/can.h> #include <libopencm3/stm32/can.h>
struct can_tx_msg { struct can_tx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
}; };
struct can_rx_msg { struct can_rx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
u8 fmi; uint8_t fmi;
}; };
struct can_tx_msg can_tx_msg; struct can_tx_msg can_tx_msg;
@@ -166,7 +166,7 @@ static void can_setup(void)
void sys_tick_handler(void) void sys_tick_handler(void)
{ {
static int temp32 = 0; static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0}; static uint8_t data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so every 100ms = 0.1s /* We call this handler every 1ms so every 100ms = 0.1s
* resulting in 100Hz message rate. * resulting in 100Hz message rate.
@@ -195,9 +195,9 @@ void sys_tick_handler(void)
void usb_lp_can_rx0_isr(void) void usb_lp_can_rx0_isr(void)
{ {
u32 id, fmi; uint32_t id, fmi;
bool ext, rtr; bool ext, rtr;
u8 length, data[8]; uint8_t length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data); can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);

View File

@@ -132,7 +132,7 @@ static void gpio_setup(void)
int main(void) int main(void)
{ {
int counter = 0; int counter = 0;
u16 rx_value = 0x42; uint16_t rx_value = 0x42;
clock_setup(); clock_setup();
gpio_setup(); gpio_setup();

View File

@@ -142,9 +142,9 @@ static void dma_setup(void)
} }
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
static int spi_dma_transceive(u16 *tx_buf, int tx_len, u16 *rx_buf, int rx_len) static int spi_dma_transceive(uint16_t *tx_buf, int tx_len, uint16_t *rx_buf, int rx_len)
#else #else
static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len) static int spi_dma_transceive(uint8_t *tx_buf, int tx_len, uint8_t *rx_buf, int rx_len)
#endif #endif
{ {
/* Check for 0 length in both tx and rx */ /* Check for 0 length in both tx and rx */
@@ -162,7 +162,7 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
* busy any longer, i.e. the last activity was verified * busy any longer, i.e. the last activity was verified
* complete elsewhere in the program. * complete elsewhere in the program.
*/ */
volatile u8 temp_data __attribute__ ((unused)); volatile uint8_t temp_data __attribute__ ((unused));
while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) { while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) {
temp_data = SPI_DR(SPI1); temp_data = SPI_DR(SPI1);
} }
@@ -178,8 +178,8 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
/* Set up rx dma, note it has higher priority to avoid overrun */ /* Set up rx dma, note it has higher priority to avoid overrun */
if (rx_len > 0) { if (rx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL2, (u32)rx_buf); dma_set_memory_address(DMA1, DMA_CHANNEL2, (uint32_t)rx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len); dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2); dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2);
@@ -195,8 +195,8 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
/* Set up tx dma */ /* Set up tx dma */
if (tx_len > 0) { if (tx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)tx_buf); dma_set_memory_address(DMA1, DMA_CHANNEL3, (uint32_t)tx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len); dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len);
dma_set_read_from_memory(DMA1, DMA_CHANNEL3); dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3);
@@ -340,11 +340,11 @@ int main(void)
/* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */ /* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
u16 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; uint16_t tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u16 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42}; uint16_t rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#else #else
u8 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; uint8_t tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u8 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42}; uint8_t rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#endif #endif
transceive_status = DONE; transceive_status = DONE;

View File

@@ -52,9 +52,9 @@ volatile trans_status transceive_status;
int rx_buf_remainder = 0; int rx_buf_remainder = 0;
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
u16 dummy_tx_buf = 0xdd; uint16_t dummy_tx_buf = 0xdd;
#else #else
u8 dummy_tx_buf = 0xdd; uint8_t dummy_tx_buf = 0xdd;
#endif #endif
int _write(int file, char *ptr, int len); int _write(int file, char *ptr, int len);
@@ -152,9 +152,9 @@ static void dma_setup(void)
} }
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
static int spi_dma_transceive(u16 *tx_buf, int tx_len, u16 *rx_buf, int rx_len) static int spi_dma_transceive(uint16_t *tx_buf, int tx_len, uint16_t *rx_buf, int rx_len)
#else #else
static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len) static int spi_dma_transceive(uint8_t *tx_buf, int tx_len, uint8_t *rx_buf, int rx_len)
#endif #endif
{ {
@@ -173,7 +173,7 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
* busy any longer, i.e. the last activity was verified * busy any longer, i.e. the last activity was verified
* complete elsewhere in the program. * complete elsewhere in the program.
*/ */
volatile u8 temp_data __attribute__ ((unused)); volatile uint8_t temp_data __attribute__ ((unused));
while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) { while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) {
temp_data = SPI_DR(SPI1); temp_data = SPI_DR(SPI1);
} }
@@ -199,8 +199,8 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
/* Set up rx dma, note it has higher priority to avoid overrun */ /* Set up rx dma, note it has higher priority to avoid overrun */
if (rx_len > 0) { if (rx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL2, (u32)rx_buf); dma_set_memory_address(DMA1, DMA_CHANNEL2, (uint32_t)rx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len); dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2); dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2);
@@ -217,8 +217,8 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
/* Set up tx dma (must always run tx to get clock signal) */ /* Set up tx dma (must always run tx to get clock signal) */
if (tx_len > 0) { if (tx_len > 0) {
/* Here we have a regular tx transfer */ /* Here we have a regular tx transfer */
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)tx_buf); dma_set_memory_address(DMA1, DMA_CHANNEL3, (uint32_t)tx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len); dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len);
dma_set_read_from_memory(DMA1, DMA_CHANNEL3); dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3);
@@ -235,8 +235,8 @@ static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
* and set the length to the rx_len to get all rx data in, while * and set the length to the rx_len to get all rx data in, while
* not incrementing the memory pointer * not incrementing the memory pointer
*/ */
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)(&dummy_tx_buf)); // Change here dma_set_memory_address(DMA1, DMA_CHANNEL3, (uint32_t)(&dummy_tx_buf)); // Change here
dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_len); // Change here dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_len); // Change here
dma_set_read_from_memory(DMA1, DMA_CHANNEL3); dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here
@@ -313,8 +313,8 @@ void dma1_channel3_isr(void)
*/ */
if (rx_buf_remainder > 0) { if (rx_buf_remainder > 0) {
dma_channel_reset(DMA1, DMA_CHANNEL3); dma_channel_reset(DMA1, DMA_CHANNEL3);
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (uint32_t)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)(&dummy_tx_buf)); // Change here dma_set_memory_address(DMA1, DMA_CHANNEL3, (uint32_t)(&dummy_tx_buf)); // Change here
dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_buf_remainder); // Change here dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_buf_remainder); // Change here
dma_set_read_from_memory(DMA1, DMA_CHANNEL3); dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here
@@ -401,11 +401,11 @@ int main(void)
/* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */ /* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
u16 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; uint16_t tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u16 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42}; uint16_t rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#else #else
u8 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; uint8_t tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u8 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42}; uint8_t rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#endif #endif
transceive_status = DONE; transceive_status = DONE;
@@ -494,9 +494,9 @@ int main(void)
/* Reset receive buffer for consistency */ /* Reset receive buffer for consistency */
for (i = 0; i < 16; i++) { for (i = 0; i < 16; i++) {
#if USE_16BIT_TRANSFERS #if USE_16BIT_TRANSFERS
tx_packet[i] = (u16)i; tx_packet[i] = (uint16_t)i;
#else #else
tx_packet[i] = (u8)i; tx_packet[i] = (uint8_t)i;
#endif #endif
rx_packet[i] = 0x42; rx_packet[i] = 0x42;
} }

View File

@@ -76,8 +76,8 @@ static void dma_write(char *data, int size)
/* Reset DMA channel*/ /* Reset DMA channel*/
dma_channel_reset(DMA1, DMA_CHANNEL7); dma_channel_reset(DMA1, DMA_CHANNEL7);
dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (u32)&USART2_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t)&USART2_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL7, (u32)data); dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)data);
dma_set_number_of_data(DMA1, DMA_CHANNEL7, size); dma_set_number_of_data(DMA1, DMA_CHANNEL7, size);
dma_set_read_from_memory(DMA1, DMA_CHANNEL7); dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
@@ -118,8 +118,8 @@ static void dma_read(char *data, int size)
/* Reset DMA channel*/ /* Reset DMA channel*/
dma_channel_reset(DMA1, DMA_CHANNEL6); dma_channel_reset(DMA1, DMA_CHANNEL6);
dma_set_peripheral_address(DMA1, DMA_CHANNEL6, (u32)&USART2_DR); dma_set_peripheral_address(DMA1, DMA_CHANNEL6, (uint32_t)&USART2_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL6, (u32)data); dma_set_memory_address(DMA1, DMA_CHANNEL6, (uint32_t)data);
dma_set_number_of_data(DMA1, DMA_CHANNEL6, size); dma_set_number_of_data(DMA1, DMA_CHANNEL6, size);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL6); dma_set_read_from_peripheral(DMA1, DMA_CHANNEL6);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL6); dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL6);

View File

@@ -81,7 +81,7 @@ static void gpio_setup(void)
void usart2_isr(void) void usart2_isr(void)
{ {
static u8 data = 'A'; static uint8_t data = 'A';
/* Check if we were called because of RXNE. */ /* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) && if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&

View File

@@ -32,13 +32,13 @@
* https://github.com/open-bldc/open-bldc/tree/master/source/libgovernor * https://github.com/open-bldc/open-bldc/tree/master/source/libgovernor
*****************************************************************************/ *****************************************************************************/
typedef s32 ring_size_t; typedef int32_t ring_size_t;
struct ring { struct ring {
u8 *data; uint8_t *data;
ring_size_t size; ring_size_t size;
u32 begin; uint32_t begin;
u32 end; uint32_t end;
}; };
#define RING_SIZE(RING) ((RING)->size - 1) #define RING_SIZE(RING) ((RING)->size - 1)
@@ -47,7 +47,7 @@ struct ring {
int _write(int file, char *ptr, int len); int _write(int file, char *ptr, int len);
static void ring_init(struct ring *ring, u8 *buf, ring_size_t size) static void ring_init(struct ring *ring, uint8_t *buf, ring_size_t size)
{ {
ring->data = buf; ring->data = buf;
ring->size = size; ring->size = size;
@@ -55,20 +55,20 @@ static void ring_init(struct ring *ring, u8 *buf, ring_size_t size)
ring->end = 0; ring->end = 0;
} }
static s32 ring_write_ch(struct ring *ring, u8 ch) static int32_t ring_write_ch(struct ring *ring, uint8_t ch)
{ {
if (((ring->end + 1) % ring->size) != ring->begin) { if (((ring->end + 1) % ring->size) != ring->begin) {
ring->data[ring->end++] = ch; ring->data[ring->end++] = ch;
ring->end %= ring->size; ring->end %= ring->size;
return (u32)ch; return (uint32_t)ch;
} }
return -1; return -1;
} }
static s32 ring_write(struct ring *ring, u8 *data, ring_size_t size) static int32_t ring_write(struct ring *ring, uint8_t *data, ring_size_t size)
{ {
s32 i; int32_t i;
for (i = 0; i < size; i++) { for (i = 0; i < size; i++) {
if (ring_write_ch(ring, data[i]) < 0) if (ring_write_ch(ring, data[i]) < 0)
@@ -78,9 +78,9 @@ static s32 ring_write(struct ring *ring, u8 *data, ring_size_t size)
return i; return i;
} }
static s32 ring_read_ch(struct ring *ring, u8 *ch) static int32_t ring_read_ch(struct ring *ring, uint8_t *ch)
{ {
s32 ret = -1; int32_t ret = -1;
if (ring->begin != ring->end) { if (ring->begin != ring->end) {
ret = ring->data[ring->begin++]; ret = ring->data[ring->begin++];
@@ -93,9 +93,9 @@ static s32 ring_read_ch(struct ring *ring, u8 *ch)
} }
/* Not used! /* Not used!
static s32 ring_read(struct ring *ring, u8 *data, ring_size_t size) static int32_t ring_read(struct ring *ring, uint8_t *data, ring_size_t size)
{ {
s32 i; int32_t i;
for (i = 0; i < size; i++) { for (i = 0; i < size; i++) {
if (ring_read_ch(ring, data + i) < 0) if (ring_read_ch(ring, data + i) < 0)
@@ -113,7 +113,7 @@ static s32 ring_read(struct ring *ring, u8 *data, ring_size_t size)
#define BUFFER_SIZE 1024 #define BUFFER_SIZE 1024
struct ring output_ring; struct ring output_ring;
u8 output_ring_buffer[BUFFER_SIZE]; uint8_t output_ring_buffer[BUFFER_SIZE];
static void clock_setup(void) static void clock_setup(void)
{ {
@@ -188,7 +188,7 @@ void usart2_isr(void)
if (((USART_CR1(USART2) & USART_CR1_TXEIE) != 0) && if (((USART_CR1(USART2) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART2) & USART_SR_TXE) != 0)) { ((USART_SR(USART2) & USART_SR_TXE) != 0)) {
s32 data; int32_t data;
data = ring_read_ch(&output_ring, NULL); data = ring_read_ch(&output_ring, NULL);
@@ -207,7 +207,7 @@ int _write(int file, char *ptr, int len)
int ret; int ret;
if (file == 1) { if (file == 1) {
ret = ring_write(&output_ring, (u8 *)ptr, len); ret = ring_write(&output_ring, (uint8_t *)ptr, len);
if (ret < 0) if (ret < 0)
ret = -ret; ret = -ret;
@@ -241,7 +241,7 @@ void sys_tick_handler(void)
static int counter = 0; static int counter = 0;
static float fcounter = 0.0; static float fcounter = 0.0;
static double dcounter = 0.0; static double dcounter = 0.0;
static u32 temp32 = 0; static uint32_t temp32 = 0;
temp32++; temp32++;

View File

@@ -49,7 +49,7 @@
* Iout = Iin ** gamma * Iout = Iin ** gamma
*/ */
#ifdef GAMMA_LINEAR #ifdef GAMMA_LINEAR
static const u16 gamma_table_linear[] = { static const uint16_t gamma_table_linear[] = {
1, 4, 9, 17, 26, 37, 51, 67, 1, 4, 9, 17, 26, 37, 51, 67,
84, 104, 126, 149, 175, 203, 233, 265, 84, 104, 126, 149, 175, 203, 233, 265,
299, 334, 372, 412, 454, 499, 545, 593, 299, 334, 372, 412, 454, 499, 545, 593,
@@ -86,7 +86,7 @@ static const u16 gamma_table_linear[] = {
#endif #endif
#ifdef GAMMA_1_3 #ifdef GAMMA_1_3
static const u16 gamma_table_1_3[] = { static const uint16_t gamma_table_1_3[] = {
/* Gamma 1.3 */ /* Gamma 1.3 */
0, 49, 120, 203, 296, 395, 501, 612, 0, 49, 120, 203, 296, 395, 501, 612,
728, 848, 973, 1101, 1233, 1368, 1506, 1648, 728, 848, 973, 1101, 1233, 1368, 1506, 1648,
@@ -124,7 +124,7 @@ static const u16 gamma_table_1_3[] = {
#endif #endif
#ifdef GAMMA_2_2 #ifdef GAMMA_2_2
static const u16 gamma_table_2_2[] = { static const uint16_t gamma_table_2_2[] = {
0, 0, 2, 4, 7, 11, 17, 24, 0, 0, 2, 4, 7, 11, 17, 24,
32, 42, 53, 65, 79, 94, 111, 129, 32, 42, 53, 65, 79, 94, 111, 129,
148, 169, 192, 216, 242, 270, 299, 330, 148, 169, 192, 216, 242, 270, 299, 330,
@@ -161,7 +161,7 @@ static const u16 gamma_table_2_2[] = {
#endif #endif
#ifdef GAMMA_2_5 #ifdef GAMMA_2_5
static const u16 gamma_table_2_5[] = { static const uint16_t gamma_table_2_5[] = {
/* gamma = 2.5 */ /* gamma = 2.5 */
0, 0, 0, 1, 2, 4, 6, 8, 0, 0, 0, 1, 2, 4, 6, 8,
11, 15, 20, 25, 31, 38, 46, 55, 11, 15, 20, 25, 31, 38, 46, 55,
@@ -199,7 +199,7 @@ static const u16 gamma_table_2_5[] = {
#endif #endif
#ifdef GAMMA_3_0 #ifdef GAMMA_3_0
static const u16 gamma_table_3_0[] = { static const uint16_t gamma_table_3_0[] = {
/* gamma = 3.0 */ /* gamma = 3.0 */
0, 0, 0, 0, 0, 0, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1,
2, 3, 4, 5, 7, 9, 11, 13, 2, 3, 4, 5, 7, 9, 11, 13,

View File

@@ -25,22 +25,22 @@
#include <libopencm3/stm32/can.h> #include <libopencm3/stm32/can.h>
struct can_tx_msg { struct can_tx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
}; };
struct can_rx_msg { struct can_rx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
u8 fmi; uint8_t fmi;
}; };
struct can_tx_msg can_tx_msg; struct can_tx_msg can_tx_msg;
@@ -151,7 +151,7 @@ static void can_setup(void)
void sys_tick_handler(void) void sys_tick_handler(void)
{ {
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0}; static uint8_t data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so every 1ms = 0.001s /* We call this handler every 1ms so every 1ms = 0.001s
* resulting in 1000Hz message rate. * resulting in 1000Hz message rate.
@@ -173,9 +173,9 @@ void sys_tick_handler(void)
void usb_lp_can_rx0_isr(void) void usb_lp_can_rx0_isr(void)
{ {
u32 id, fmi; uint32_t id, fmi;
bool ext, rtr; bool ext, rtr;
u8 length, data[8]; uint8_t length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data); can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);

View File

@@ -23,7 +23,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h> #include <libopencm3/cm3/systick.h>
u32 temp32; uint32_t temp32;
static void gpio_setup(void) static void gpio_setup(void)
{ {

View File

@@ -26,22 +26,22 @@
#include <libopencm3/stm32/can.h> #include <libopencm3/stm32/can.h>
struct can_tx_msg { struct can_tx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
}; };
struct can_rx_msg { struct can_rx_msg {
u32 std_id; uint32_t std_id;
u32 ext_id; uint32_t ext_id;
u8 ide; uint8_t ide;
u8 rtr; uint8_t rtr;
u8 dlc; uint8_t dlc;
u8 data[8]; uint8_t data[8];
u8 fmi; uint8_t fmi;
}; };
struct can_tx_msg can_tx_msg; struct can_tx_msg can_tx_msg;
@@ -151,7 +151,7 @@ static void can_setup(void)
void sys_tick_handler(void) void sys_tick_handler(void)
{ {
static int temp32 = 0; static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0}; static uint8_t data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */ /* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000) if (++temp32 != 1000)
@@ -177,9 +177,9 @@ void sys_tick_handler(void)
void usb_lp_can_rx0_isr(void) void usb_lp_can_rx0_isr(void)
{ {
u32 id, fmi; uint32_t id, fmi;
bool ext, rtr; bool ext, rtr;
u8 length, data[8]; uint8_t length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data); can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);

View File

@@ -49,7 +49,7 @@
* Iout = Iin ** gamma * Iout = Iin ** gamma
*/ */
#ifdef GAMMA_LINEAR #ifdef GAMMA_LINEAR
static const u16 gamma_table_linear[] = { static const uint16_t gamma_table_linear[] = {
1, 4, 9, 17, 26, 37, 51, 67, 1, 4, 9, 17, 26, 37, 51, 67,
84, 104, 126, 149, 175, 203, 233, 265, 84, 104, 126, 149, 175, 203, 233, 265,
299, 334, 372, 412, 454, 499, 545, 593, 299, 334, 372, 412, 454, 499, 545, 593,
@@ -86,7 +86,7 @@ static const u16 gamma_table_linear[] = {
#endif #endif
#ifdef GAMMA_1_3 #ifdef GAMMA_1_3
static const u16 gamma_table_1_3[] = { static const uint16_t gamma_table_1_3[] = {
/* Gamma 1.3 */ /* Gamma 1.3 */
0, 49, 120, 203, 296, 395, 501, 612, 0, 49, 120, 203, 296, 395, 501, 612,
728, 848, 973, 1101, 1233, 1368, 1506, 1648, 728, 848, 973, 1101, 1233, 1368, 1506, 1648,
@@ -124,7 +124,7 @@ static const u16 gamma_table_1_3[] = {
#endif #endif
#ifdef GAMMA_2_2 #ifdef GAMMA_2_2
static const u16 gamma_table_2_2[] = { static const uint16_t gamma_table_2_2[] = {
0, 0, 2, 4, 7, 11, 17, 24, 0, 0, 2, 4, 7, 11, 17, 24,
32, 42, 53, 65, 79, 94, 111, 129, 32, 42, 53, 65, 79, 94, 111, 129,
148, 169, 192, 216, 242, 270, 299, 330, 148, 169, 192, 216, 242, 270, 299, 330,
@@ -161,7 +161,7 @@ static const u16 gamma_table_2_2[] = {
#endif #endif
#ifdef GAMMA_2_5 #ifdef GAMMA_2_5
static const u16 gamma_table_2_5[] = { static const uint16_t gamma_table_2_5[] = {
/* gamma = 2.5 */ /* gamma = 2.5 */
0, 0, 0, 1, 2, 4, 6, 8, 0, 0, 0, 1, 2, 4, 6, 8,
11, 15, 20, 25, 31, 38, 46, 55, 11, 15, 20, 25, 31, 38, 46, 55,
@@ -199,7 +199,7 @@ static const u16 gamma_table_2_5[] = {
#endif #endif
#ifdef GAMMA_3_0 #ifdef GAMMA_3_0
static const u16 gamma_table_3_0[] = { static const uint16_t gamma_table_3_0[] = {
/* gamma = 3.0 */ /* gamma = 3.0 */
0, 0, 0, 0, 0, 0, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1,
2, 3, 4, 5, 7, 9, 11, 13, 2, 3, 4, 5, 7, 9, 11, 13,

View File

@@ -24,7 +24,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h> #include <libopencm3/cm3/systick.h>
u32 temp32; uint32_t temp32;
static void gpio_setup(void) static void gpio_setup(void)
{ {

View File

@@ -77,7 +77,7 @@ static void gpio_setup(void)
void usart1_isr(void) void usart1_isr(void)
{ {
static u8 data = 'A'; static uint8_t data = 'A';
/* Check if we were called because of RXNE. */ /* Check if we were called because of RXNE. */
if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) && if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) &&

View File

@@ -85,10 +85,10 @@ static void adc_setup(void)
adc_calibration(ADC1); adc_calibration(ADC1);
} }
static void my_usart_print_int(u32 usart, int value) static void my_usart_print_int(uint32_t usart, int value)
{ {
s8 i; int8_t i;
u8 nr_digits = 0; uint8_t nr_digits = 0;
char buffer[25]; char buffer[25];
if (value < 0) { if (value < 0) {
@@ -107,8 +107,8 @@ static void my_usart_print_int(u32 usart, int value)
int main(void) int main(void)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
u16 temperature; uint16_t temperature;
rcc_clock_setup_in_hse_16mhz_out_72mhz(); rcc_clock_setup_in_hse_16mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -57,7 +57,7 @@ static void gpio_setup(void)
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7); GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
} }
static void my_usart_print_string(u32 usart, char *s) static void my_usart_print_string(uint32_t usart, char *s)
{ {
while (*s != 0) { while (*s != 0) {
usart_send(usart, *s); usart_send(usart, *s);
@@ -107,10 +107,10 @@ int main(void)
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1); dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
/* We want to transfer string s1. */ /* We want to transfer string s1. */
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (u32)&s1); dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t)&s1);
/* Destination should be string s2. */ /* Destination should be string s2. */
dma_set_memory_address(DMA1, DMA_CHANNEL1, (u32)&s2); dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t)&s2);
/* /*
* Set number of DATA to transfer. * Set number of DATA to transfer.

View File

@@ -19,13 +19,13 @@
#include "./dogm128.h" #include "./dogm128.h"
u8 dogm128_ram[1024]; uint8_t dogm128_ram[1024];
u8 dogm128_cursor_x; uint8_t dogm128_cursor_x;
u8 dogm128_cursor_y; uint8_t dogm128_cursor_y;
void dogm128_send_command(u8 command) void dogm128_send_command(uint8_t command)
{ {
u32 i; uint32_t i;
gpio_clear(DOGM128_A0_PORT, DOGM128_A0_PIN); /* A0 low for commands */ gpio_clear(DOGM128_A0_PORT, DOGM128_A0_PIN); /* A0 low for commands */
spi_send(DOGM128_SPI, command); spi_send(DOGM128_SPI, command);
@@ -34,9 +34,9 @@ void dogm128_send_command(u8 command)
; ;
} }
void dogm128_send_data(u8 data) void dogm128_send_data(uint8_t data)
{ {
u32 i; uint32_t i;
gpio_set(DOGM128_A0_PORT, DOGM128_A0_PIN); /* A0 high for data */ gpio_set(DOGM128_A0_PORT, DOGM128_A0_PIN); /* A0 high for data */
spi_send(DOGM128_SPI, data); spi_send(DOGM128_SPI, data);
@@ -47,7 +47,7 @@ void dogm128_send_data(u8 data)
void dogm128_init(void) void dogm128_init(void)
{ {
u32 i; uint32_t i;
/* Reset the display (reset low for dogm128). */ /* Reset the display (reset low for dogm128). */
gpio_clear(DOGM128_RESET_PORT, DOGM128_RESET_PIN); gpio_clear(DOGM128_RESET_PORT, DOGM128_RESET_PIN);
@@ -84,9 +84,9 @@ void dogm128_init(void)
spi_set_nss_high(DOGM128_SPI); spi_set_nss_high(DOGM128_SPI);
} }
void dogm128_print_char(u8 data) void dogm128_print_char(uint8_t data)
{ {
u8 i, page, shift, xcoord, ycoord; uint8_t i, page, shift, xcoord, ycoord;
xcoord = dogm128_cursor_x; xcoord = dogm128_cursor_x;
ycoord = dogm128_cursor_y; ycoord = dogm128_cursor_y;
@@ -128,7 +128,7 @@ void dogm128_print_char(u8 data)
} }
} }
void dogm128_set_cursor(u8 xcoord, u8 ycoord) void dogm128_set_cursor(uint8_t xcoord, uint8_t ycoord)
{ {
dogm128_cursor_x = xcoord; dogm128_cursor_x = xcoord;
dogm128_cursor_y = ycoord; dogm128_cursor_y = ycoord;
@@ -142,13 +142,13 @@ void dogm128_print_string(char *s)
} }
} }
void dogm128_set_dot(u8 xcoord, u8 ycoord) void dogm128_set_dot(uint8_t xcoord, uint8_t ycoord)
{ {
dogm128_ram[(((63 - ycoord) / 8) * 128) + xcoord] |= dogm128_ram[(((63 - ycoord) / 8) * 128) + xcoord] |=
(1 << ((63 - ycoord) % 8)); (1 << ((63 - ycoord) % 8));
} }
void dogm128_clear_dot(u8 xcoord, u8 ycoord) void dogm128_clear_dot(uint8_t xcoord, uint8_t ycoord)
{ {
dogm128_ram[(((63 - ycoord) / 8) * 128) + xcoord] &= dogm128_ram[(((63 - ycoord) / 8) * 128) + xcoord] &=
~(1 << ((63 - ycoord) % 8)); ~(1 << ((63 - ycoord) % 8));
@@ -156,7 +156,7 @@ void dogm128_clear_dot(u8 xcoord, u8 ycoord)
void dogm128_update_display(void) void dogm128_update_display(void)
{ {
u8 page, column; uint8_t page, column;
/* Tell the display that we want to start. */ /* Tell the display that we want to start. */
spi_set_nss_low(DOGM128_SPI); spi_set_nss_low(DOGM128_SPI);
@@ -196,7 +196,7 @@ void dogm128_clear(void)
* little bit. * little bit.
*/ */
const u8 dogm128_font[96][6] = { const uint8_t dogm128_font[96][6] = {
/* 20 SPACE */ {0x00, 0x00, 0x00, 0xAA, 0xAA, 0xAA}, /* 20 SPACE */ {0x00, 0x00, 0x00, 0xAA, 0xAA, 0xAA},
/* 21 ! */ {0x5E, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA}, /* 21 ! */ {0x5E, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA},

View File

@@ -69,18 +69,18 @@
#define DOGM128_STATIC_INDICATOR_ON 0xAD #define DOGM128_STATIC_INDICATOR_ON 0xAD
#define DOGM128_BOOSTER_RATIO_SET 0xF8 #define DOGM128_BOOSTER_RATIO_SET 0xF8
extern const u8 dogm128_font[96][6]; extern const uint8_t dogm128_font[96][6];
extern u8 dogm128_ram[1024]; extern uint8_t dogm128_ram[1024];
extern u8 dogm128_cursor_x; extern uint8_t dogm128_cursor_x;
extern u8 dogm128_cursor_y; extern uint8_t dogm128_cursor_y;
void dogm128_send_command(u8 command); void dogm128_send_command(uint8_t command);
void dogm128_set_cursor(u8 xcoord, u8 ycoord); void dogm128_set_cursor(uint8_t xcoord, uint8_t ycoord);
void dogm128_print_char(u8 data); void dogm128_print_char(uint8_t data);
void dogm128_print_string(char *s); void dogm128_print_string(char *s);
void dogm128_set_dot(u8 xcoord, u8 ycoord); void dogm128_set_dot(uint8_t xcoord, uint8_t ycoord);
void dogm128_clear_dot(u8 xcoord, u8 ycoord); void dogm128_clear_dot(uint8_t xcoord, uint8_t ycoord);
void dogm128_send_data(u8 data); void dogm128_send_data(uint8_t data);
void dogm128_init(void); void dogm128_init(void);
void dogm128_update_display(void); void dogm128_update_display(void);
void dogm128_clear(void); void dogm128_clear(void);

View File

@@ -105,7 +105,7 @@ static void i2c_setup(void)
int main(void) int main(void)
{ {
int i = 0; int i = 0;
u16 temperature; uint16_t temperature;
rcc_clock_setup_in_hse_16mhz_out_72mhz(); rcc_clock_setup_in_hse_16mhz_out_72mhz();
gpio_setup(); gpio_setup();

View File

@@ -20,9 +20,9 @@
#include <libopencm3/stm32/i2c.h> #include <libopencm3/stm32/i2c.h>
#include "stts75.h" #include "stts75.h"
void stts75_write_config(u32 i2c, u8 sensor) void stts75_write_config(uint32_t i2c, uint8_t sensor)
{ {
u32 reg32 __attribute__((unused)); uint32_t reg32 __attribute__((unused));
/* Send START condition. */ /* Send START condition. */
i2c_send_start(i2c); i2c_send_start(i2c);
@@ -51,9 +51,9 @@ void stts75_write_config(u32 i2c, u8 sensor)
i2c_send_stop(i2c); i2c_send_stop(i2c);
} }
void stts75_write_temp_os(u32 i2c, u8 sensor, u16 temp_os) void stts75_write_temp_os(uint32_t i2c, uint8_t sensor, uint16_t temp_os)
{ {
u32 reg32 __attribute__((unused)); uint32_t reg32 __attribute__((unused));
/* Send START condition. */ /* Send START condition. */
i2c_send_start(i2c); i2c_send_start(i2c);
@@ -74,9 +74,9 @@ void stts75_write_temp_os(u32 i2c, u8 sensor, u16 temp_os)
/* Sending the data. */ /* Sending the data. */
i2c_send_data(i2c, 0x3); /* OvertemperatureShutdown register */ i2c_send_data(i2c, 0x3); /* OvertemperatureShutdown register */
while (!(I2C_SR1(i2c) & I2C_SR1_BTF)); while (!(I2C_SR1(i2c) & I2C_SR1_BTF));
i2c_send_data(i2c, (u8)(temp_os >> 8)); /* MSB */ i2c_send_data(i2c, (uint8_t)(temp_os >> 8)); /* MSB */
while (!(I2C_SR1(i2c) & I2C_SR1_BTF)); while (!(I2C_SR1(i2c) & I2C_SR1_BTF));
i2c_send_data(i2c, (u8)(temp_os & 0xff00)); /* LSB */ i2c_send_data(i2c, (uint8_t)(temp_os & 0xff00)); /* LSB */
/* After the last byte we have to wait for TxE too. */ /* After the last byte we have to wait for TxE too. */
while (!(I2C_SR1(i2c) & (I2C_SR1_BTF | I2C_SR1_TxE))); while (!(I2C_SR1(i2c) & (I2C_SR1_BTF | I2C_SR1_TxE)));
@@ -84,9 +84,9 @@ void stts75_write_temp_os(u32 i2c, u8 sensor, u16 temp_os)
i2c_send_stop(i2c); i2c_send_stop(i2c);
} }
void stts75_write_temp_hyst(u32 i2c, u8 sensor, u16 temp_hyst) void stts75_write_temp_hyst(uint32_t i2c, uint8_t sensor, uint16_t temp_hyst)
{ {
u32 reg32 __attribute__((unused)); uint32_t reg32 __attribute__((unused));
/* Send START condition. */ /* Send START condition. */
i2c_send_start(i2c); i2c_send_start(i2c);
@@ -107,9 +107,9 @@ void stts75_write_temp_hyst(u32 i2c, u8 sensor, u16 temp_hyst)
/* Sending the data. */ /* Sending the data. */
i2c_send_data(i2c, 0x2); /* TemperatureHysteresis register */ i2c_send_data(i2c, 0x2); /* TemperatureHysteresis register */
while (!(I2C_SR1(i2c) & I2C_SR1_BTF)); while (!(I2C_SR1(i2c) & I2C_SR1_BTF));
i2c_send_data(i2c, (u8)(temp_hyst >> 8)); /* MSB */ i2c_send_data(i2c, (uint8_t)(temp_hyst >> 8)); /* MSB */
while (!(I2C_SR1(i2c) & I2C_SR1_BTF)); while (!(I2C_SR1(i2c) & I2C_SR1_BTF));
i2c_send_data(i2c, (u8)(temp_hyst & 0xff00)); /* LSB */ i2c_send_data(i2c, (uint8_t)(temp_hyst & 0xff00)); /* LSB */
/* After the last byte we have to wait for TxE too. */ /* After the last byte we have to wait for TxE too. */
while (!(I2C_SR1(i2c) & (I2C_SR1_BTF | I2C_SR1_TxE))); while (!(I2C_SR1(i2c) & (I2C_SR1_BTF | I2C_SR1_TxE)));
@@ -117,10 +117,10 @@ void stts75_write_temp_hyst(u32 i2c, u8 sensor, u16 temp_hyst)
i2c_send_stop(i2c); i2c_send_stop(i2c);
} }
u16 stts75_read_temperature(u32 i2c, u8 sensor) uint16_t stts75_read_temperature(uint32_t i2c, uint8_t sensor)
{ {
u32 reg32 __attribute__((unused)); uint32_t reg32 __attribute__((unused));
u16 temperature; uint16_t temperature;
/* Send START condition. */ /* Send START condition. */
i2c_send_start(i2c); i2c_send_start(i2c);
@@ -172,7 +172,7 @@ u16 stts75_read_temperature(u32 i2c, u8 sensor)
/* Now the slave should begin to send us the first byte. Await BTF. */ /* Now the slave should begin to send us the first byte. Await BTF. */
while (!(I2C_SR1(i2c) & I2C_SR1_BTF)); while (!(I2C_SR1(i2c) & I2C_SR1_BTF));
temperature = (u16)(I2C_DR(i2c) << 8); /* MSB */ temperature = (uint16_t)(I2C_DR(i2c) << 8); /* MSB */
/* /*
* Yes they mean it: we have to generate the STOP condition before * Yes they mean it: we have to generate the STOP condition before

View File

@@ -31,9 +31,9 @@
#define STTS75_SENSOR6 0x4e #define STTS75_SENSOR6 0x4e
#define STTS75_SENSOR7 0x4f #define STTS75_SENSOR7 0x4f
void stts75_write_config(u32 i2c, u8 sensor); void stts75_write_config(uint32_t i2c, uint8_t sensor);
void stts75_write_temp_os(u32 i2c, u8 sensor, u16 temp_os); void stts75_write_temp_os(uint32_t i2c, uint8_t sensor, uint16_t temp_os);
void stts75_write_temp_hyst(u32 i2c, u8 sensor, u16 temp_hyst); void stts75_write_temp_hyst(uint32_t i2c, uint8_t sensor, uint16_t temp_hyst);
u16 stts75_read_temperature(u32 i2c, u8 sensor); uint16_t stts75_read_temperature(uint32_t i2c, uint8_t sensor);
#endif #endif

View File

@@ -70,7 +70,7 @@ static void nvic_setup(void)
void rtc_isr(void) void rtc_isr(void)
{ {
volatile u32 j = 0, c = 0; volatile uint32_t j = 0, c = 0;
/* The interrupt flag isn't cleared by hardware, we have to do it. */ /* The interrupt flag isn't cleared by hardware, we have to do it. */
rtc_clear_flag(RTC_SEC); rtc_clear_flag(RTC_SEC);

View File

@@ -23,7 +23,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h> #include <libopencm3/cm3/systick.h>
u32 temp32; uint32_t temp32;
static void gpio_setup(void) static void gpio_setup(void)
{ {

View File

@@ -164,10 +164,10 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
(void)buf; (void)buf;
@@ -203,7 +203,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
return 0; return 0;
} }
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep) static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{ {
(void)ep; (void)ep;
@@ -216,7 +216,7 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
} }
} }
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue) static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;

View File

@@ -32,15 +32,15 @@
#define CMD_ERASE 0x41 #define CMD_ERASE 0x41
/* We need a special large control buffer for this device: */ /* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024]; uint8_t usbd_control_buffer[1024];
static enum dfu_state usbdfu_state = STATE_DFU_IDLE; static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static struct { static struct {
u8 buf[sizeof(usbd_control_buffer)]; uint8_t buf[sizeof(usbd_control_buffer)];
u16 len; uint16_t len;
u32 addr; uint32_t addr;
u16 blocknum; uint16_t blocknum;
} prog; } prog;
const struct usb_device_descriptor dev = { const struct usb_device_descriptor dev = {
@@ -113,7 +113,7 @@ static const char *usb_strings[] = {
"@Internal Flash /0x08000000/8*001Ka,56*001Kg", "@Internal Flash /0x08000000/8*001Ka,56*001Kg",
}; };
static u8 usbdfu_getstatus(u32 *bwPollTimeout) static uint8_t usbdfu_getstatus(uint32_t *bwPollTimeout)
{ {
switch (usbdfu_state) { switch (usbdfu_state) {
case STATE_DFU_DNLOAD_SYNC: case STATE_DFU_DNLOAD_SYNC:
@@ -142,20 +142,20 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
switch (prog.buf[0]) { switch (prog.buf[0]) {
case CMD_ERASE: case CMD_ERASE:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
flash_erase_page(*dat); flash_erase_page(*dat);
} }
case CMD_SETADDR: case CMD_SETADDR:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
prog.addr = *dat; prog.addr = *dat;
} }
} }
} else { } else {
u32 baseaddr = prog.addr + ((prog.blocknum - 2) * uint32_t baseaddr = prog.addr + ((prog.blocknum - 2) *
dfu_function.wTransferSize); dfu_function.wTransferSize);
for (i = 0; i < prog.len; i += 2) { for (i = 0; i < prog.len; i += 2) {
u16 *dat = (u16 *)(prog.buf + i); uint16_t *dat = (uint16_t *)(prog.buf + i);
flash_program_half_word(baseaddr + i, flash_program_half_word(baseaddr + i,
*dat); *dat);
} }
@@ -174,8 +174,8 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
} }
} }
static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)usbd_dev; (void)usbd_dev;
@@ -208,7 +208,7 @@ static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *
/* Upload not supported for now. */ /* Upload not supported for now. */
return 0; return 0;
case DFU_GETSTATUS: { case DFU_GETSTATUS: {
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout); (*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF; (*buf)[1] = bwPollTimeout & 0xFF;
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF; (*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
@@ -237,12 +237,12 @@ int main(void)
if (!gpio_get(GPIOA, GPIO10)) { if (!gpio_get(GPIOA, GPIO10)) {
/* Boot the application if it's valid. */ /* Boot the application if it's valid. */
if ((*(volatile u32 *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) { if ((*(volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address. */ /* Set vector table base address. */
SCB_VTOR = APP_ADDRESS & 0xFFFF; SCB_VTOR = APP_ADDRESS & 0xFFFF;
/* Initialise master stack pointer. */ /* Initialise master stack pointer. */
asm volatile("msr msp, %0"::"g" asm volatile("msr msp, %0"::"g"
(*(volatile u32 *)APP_ADDRESS)); (*(volatile uint32_t *)APP_ADDRESS));
/* Jump to application. */ /* Jump to application. */
(*(void (**)())(APP_ADDRESS + 4))(); (*(void (**)())(APP_ADDRESS + 4))();
} }

View File

@@ -53,7 +53,7 @@ const struct usb_device_descriptor dev_descr = {
}; };
/* I have no idea what this means. I haven't read the HID spec. */ /* I have no idea what this means. I haven't read the HID spec. */
static const u8 hid_report_descriptor[] = { static const uint8_t hid_report_descriptor[] = {
0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01, 0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03, 0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01, 0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
@@ -69,8 +69,8 @@ static const u8 hid_report_descriptor[] = {
static const struct { static const struct {
struct usb_hid_descriptor hid_descriptor; struct usb_hid_descriptor hid_descriptor;
struct { struct {
u8 bReportDescriptorType; uint8_t bReportDescriptorType;
u16 wDescriptorLength; uint16_t wDescriptorLength;
} __attribute__((packed)) hid_report; } __attribute__((packed)) hid_report;
} __attribute__((packed)) hid_function = { } __attribute__((packed)) hid_function = {
.hid_descriptor = { .hid_descriptor = {
@@ -172,9 +172,9 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *, struct usb_setup_data *)) void (**complete)(usbd_device *, struct usb_setup_data *))
{ {
(void)complete; (void)complete;
@@ -186,7 +186,7 @@ static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, u8
return 0; return 0;
/* Handle the HID report descriptor. */ /* Handle the HID report descriptor. */
*buf = (u8 *)hid_report_descriptor; *buf = (uint8_t *)hid_report_descriptor;
*len = sizeof(hid_report_descriptor); *len = sizeof(hid_report_descriptor);
return 1; return 1;
@@ -205,7 +205,7 @@ static void dfu_detach_complete(usbd_device *dev, struct usb_setup_data *req)
scb_reset_core(); scb_reset_core();
} }
static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *, struct usb_setup_data *)) void (**complete)(usbd_device *, struct usb_setup_data *))
{ {
(void)buf; (void)buf;
@@ -221,7 +221,7 @@ static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, u8
} }
#endif #endif
static void hid_set_config(usbd_device *dev, u16 wValue) static void hid_set_config(usbd_device *dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;
(void)dev; (void)dev;
@@ -273,7 +273,7 @@ void sys_tick_handler(void)
{ {
static int x = 0; static int x = 0;
static int dir = 1; static int dir = 1;
u8 buf[4] = {0, 0, 0, 0}; uint8_t buf[4] = {0, 0, 0, 0};
buf[1] = dir; buf[1] = dir;
x += dir; x += dir;

View File

@@ -23,7 +23,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/exti.h> #include <libopencm3/stm32/exti.h>
u16 exti_line_state; uint16_t exti_line_state;
/* Set STM32 to 72 MHz. */ /* Set STM32 to 72 MHz. */
static void clock_setup(void) static void clock_setup(void)

View File

@@ -23,7 +23,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/exti.h> #include <libopencm3/stm32/exti.h>
u16 exti_line_state; uint16_t exti_line_state;
/* Set STM32 to 72 MHz. */ /* Set STM32 to 72 MHz. */
static void clock_setup(void) static void clock_setup(void)

View File

@@ -26,7 +26,7 @@
#define FALLING 0 #define FALLING 0
#define RISING 1 #define RISING 1
u16 exti_direction = FALLING; uint16_t exti_direction = FALLING;
/* Set STM32 to 72 MHz. */ /* Set STM32 to 72 MHz. */
static void clock_setup(void) static void clock_setup(void)

View File

@@ -57,9 +57,9 @@
} }
struct color { struct color {
u8 r; uint8_t r;
u8 g; uint8_t g;
u8 b; uint8_t b;
}; };
/* Set STM32 to 72 MHz. */ /* Set STM32 to 72 MHz. */

View File

@@ -26,7 +26,7 @@
#define FALLING 0 #define FALLING 0
#define RISING 1 #define RISING 1
u16 exti_direction = FALLING; uint16_t exti_direction = FALLING;
static void clock_setup(void) static void clock_setup(void)
{ {

View File

@@ -23,7 +23,7 @@
#include <libopencm3/cm3/nvic.h> #include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/exti.h> #include <libopencm3/stm32/exti.h>
u16 frequency_sequence[18] = { uint16_t frequency_sequence[18] = {
1000, 1000,
500, 500,
1000, 1000,
@@ -46,9 +46,9 @@ u16 frequency_sequence[18] = {
int frequency_sel = 0; int frequency_sel = 0;
u16 compare_time; uint16_t compare_time;
u16 new_time; uint16_t new_time;
u16 frequency; uint16_t frequency;
int debug = 0; int debug = 0;
static void clock_setup(void) static void clock_setup(void)

View File

@@ -53,7 +53,7 @@ static void trace_setup(void)
/* Unlock access to ITM registers. */ /* Unlock access to ITM registers. */
/* FIXME: Magic numbers... Is this Cortex-M3 generic? */ /* FIXME: Magic numbers... Is this Cortex-M3 generic? */
*((volatile u32 *)0xE0000FB0) = 0xC5ACCE55; *((volatile uint32_t *)0xE0000FB0) = 0xC5ACCE55;
/* Enable ITM with ID = 1. */ /* Enable ITM with ID = 1. */
ITM_TCR = (1 << 16) | ITM_TCR_ITMENA; ITM_TCR = (1 << 16) | ITM_TCR_ITMENA;

View File

@@ -73,7 +73,7 @@ static void gpio_setup(void)
void usart1_isr(void) void usart1_isr(void)
{ {
static u8 data = 'A'; static uint8_t data = 'A';
/* Check if we were called because of RXNE. */ /* Check if we were called because of RXNE. */
if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) && if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) &&

View File

@@ -32,20 +32,20 @@
* https://github.com/open-bldc/open-bldc/tree/master/source/libgovernor * https://github.com/open-bldc/open-bldc/tree/master/source/libgovernor
*****************************************************************************/ *****************************************************************************/
typedef s32 ring_size_t; typedef int32_t ring_size_t;
struct ring { struct ring {
u8 *data; uint8_t *data;
ring_size_t size; ring_size_t size;
u32 begin; uint32_t begin;
u32 end; uint32_t end;
}; };
#define RING_SIZE(RING) ((RING)->size - 1) #define RING_SIZE(RING) ((RING)->size - 1)
#define RING_DATA(RING) (RING)->data #define RING_DATA(RING) (RING)->data
#define RING_EMPTY(RING) ((RING)->begin == (RING)->end) #define RING_EMPTY(RING) ((RING)->begin == (RING)->end)
static void ring_init(struct ring *ring, u8 *buf, ring_size_t size) static void ring_init(struct ring *ring, uint8_t *buf, ring_size_t size)
{ {
ring->data = buf; ring->data = buf;
ring->size = size; ring->size = size;
@@ -53,20 +53,20 @@ static void ring_init(struct ring *ring, u8 *buf, ring_size_t size)
ring->end = 0; ring->end = 0;
} }
static s32 ring_write_ch(struct ring *ring, u8 ch) static int32_t ring_write_ch(struct ring *ring, uint8_t ch)
{ {
if (((ring->end + 1) % ring->size) != ring->begin) { if (((ring->end + 1) % ring->size) != ring->begin) {
ring->data[ring->end++] = ch; ring->data[ring->end++] = ch;
ring->end %= ring->size; ring->end %= ring->size;
return (u32)ch; return (uint32_t)ch;
} }
return -1; return -1;
} }
static s32 ring_write(struct ring *ring, u8 *data, ring_size_t size) static int32_t ring_write(struct ring *ring, uint8_t *data, ring_size_t size)
{ {
s32 i; int32_t i;
for (i = 0; i < size; i++) { for (i = 0; i < size; i++) {
if (ring_write_ch(ring, data[i]) < 0) if (ring_write_ch(ring, data[i]) < 0)
@@ -76,9 +76,9 @@ static s32 ring_write(struct ring *ring, u8 *data, ring_size_t size)
return i; return i;
} }
static s32 ring_read_ch(struct ring *ring, u8 *ch) static int32_t ring_read_ch(struct ring *ring, uint8_t *ch)
{ {
s32 ret = -1; int32_t ret = -1;
if (ring->begin != ring->end) { if (ring->begin != ring->end) {
ret = ring->data[ring->begin++]; ret = ring->data[ring->begin++];
@@ -91,9 +91,9 @@ static s32 ring_read_ch(struct ring *ring, u8 *ch)
} }
/* Not used! /* Not used!
static s32 ring_read(struct ring *ring, u8 *data, ring_size_t size) static int32_t ring_read(struct ring *ring, uint8_t *data, ring_size_t size)
{ {
s32 i; int32_t i;
for (i = 0; i < size; i++) { for (i = 0; i < size; i++) {
if (ring_read_ch(ring, data + i) < 0) if (ring_read_ch(ring, data + i) < 0)
@@ -111,7 +111,7 @@ static s32 ring_read(struct ring *ring, u8 *data, ring_size_t size)
#define BUFFER_SIZE 1024 #define BUFFER_SIZE 1024
struct ring output_ring; struct ring output_ring;
u8 output_ring_buffer[BUFFER_SIZE]; uint8_t output_ring_buffer[BUFFER_SIZE];
int _write(int file, char *ptr, int len); int _write(int file, char *ptr, int len);
@@ -187,7 +187,7 @@ void usart1_isr(void)
if (((USART_CR1(USART1) & USART_CR1_TXEIE) != 0) && if (((USART_CR1(USART1) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART1) & USART_SR_TXE) != 0)) { ((USART_SR(USART1) & USART_SR_TXE) != 0)) {
s32 data; int32_t data;
data = ring_read_ch(&output_ring, NULL); data = ring_read_ch(&output_ring, NULL);
@@ -206,7 +206,7 @@ int _write(int file, char *ptr, int len)
int ret; int ret;
if (file == 1) { if (file == 1) {
ret = ring_write(&output_ring, (u8 *)ptr, len); ret = ring_write(&output_ring, (uint8_t *)ptr, len);
if (ret < 0) if (ret < 0)
ret = -ret; ret = -ret;
@@ -240,7 +240,7 @@ void sys_tick_handler(void)
static int counter = 0; static int counter = 0;
static float fcounter = 0.0; static float fcounter = 0.0;
static double dcounter = 0.0; static double dcounter = 0.0;
static u32 temp32 = 0; static uint32_t temp32 = 0;
temp32++; temp32++;

View File

@@ -164,10 +164,10 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
(void)buf; (void)buf;
@@ -202,7 +202,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
return 0; return 0;
} }
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep) static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{ {
(void)ep; (void)ep;
(void)usbd_dev; (void)usbd_dev;
@@ -216,7 +216,7 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
} }
} }
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue) static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;
(void)usbd_dev; (void)usbd_dev;

View File

@@ -32,15 +32,15 @@
#define CMD_ERASE 0x41 #define CMD_ERASE 0x41
/* We need a special large control buffer for this device: */ /* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024]; uint8_t usbd_control_buffer[1024];
static enum dfu_state usbdfu_state = STATE_DFU_IDLE; static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static struct { static struct {
u8 buf[sizeof(usbd_control_buffer)]; uint8_t buf[sizeof(usbd_control_buffer)];
u16 len; uint16_t len;
u32 addr; uint32_t addr;
u16 blocknum; uint16_t blocknum;
} prog; } prog;
const struct usb_device_descriptor dev = { const struct usb_device_descriptor dev = {
@@ -113,7 +113,7 @@ static const char *usb_strings[] = {
"@Internal Flash /0x08000000/8*001Ka,56*001Kg", "@Internal Flash /0x08000000/8*001Ka,56*001Kg",
}; };
static u8 usbdfu_getstatus(usbd_device *usbd_dev, u32 *bwPollTimeout) static uint8_t usbdfu_getstatus(usbd_device *usbd_dev, uint32_t *bwPollTimeout)
{ {
(void)usbd_dev; (void)usbd_dev;
@@ -144,20 +144,20 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
switch (prog.buf[0]) { switch (prog.buf[0]) {
case CMD_ERASE: case CMD_ERASE:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
flash_erase_page(*dat); flash_erase_page(*dat);
} }
case CMD_SETADDR: case CMD_SETADDR:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
prog.addr = *dat; prog.addr = *dat;
} }
} }
} else { } else {
u32 baseaddr = prog.addr + ((prog.blocknum - 2) * uint32_t baseaddr = prog.addr + ((prog.blocknum - 2) *
dfu_function.wTransferSize); dfu_function.wTransferSize);
for (i = 0; i < prog.len; i += 2) { for (i = 0; i < prog.len; i += 2) {
u16 *dat = (u16 *)(prog.buf + i); uint16_t *dat = (uint16_t *)(prog.buf + i);
flash_program_half_word(baseaddr + i, flash_program_half_word(baseaddr + i,
*dat); *dat);
} }
@@ -176,8 +176,8 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
} }
} }
static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
if ((req->bmRequestType & 0x7F) != 0x21) if ((req->bmRequestType & 0x7F) != 0x21)
return 0; /* Only accept class request. */ return 0; /* Only accept class request. */
@@ -208,7 +208,7 @@ static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *
/* Upload not supported for now. */ /* Upload not supported for now. */
return 0; return 0;
case DFU_GETSTATUS: { case DFU_GETSTATUS: {
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(usbd_dev, &bwPollTimeout); (*buf)[0] = usbdfu_getstatus(usbd_dev, &bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF; (*buf)[1] = bwPollTimeout & 0xFF;
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF; (*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
@@ -237,12 +237,12 @@ int main(void)
if (!gpio_get(GPIOA, GPIO10)) { if (!gpio_get(GPIOA, GPIO10)) {
/* Boot the application if it's valid. */ /* Boot the application if it's valid. */
if ((*(volatile u32 *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) { if ((*(volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address. */ /* Set vector table base address. */
SCB_VTOR = APP_ADDRESS & 0xFFFF; SCB_VTOR = APP_ADDRESS & 0xFFFF;
/* Initialise master stack pointer. */ /* Initialise master stack pointer. */
asm volatile("msr msp, %0"::"g" asm volatile("msr msp, %0"::"g"
(*(volatile u32 *)APP_ADDRESS)); (*(volatile uint32_t *)APP_ADDRESS));
/* Jump to application. */ /* Jump to application. */
(*(void (**)())(APP_ADDRESS + 4))(); (*(void (**)())(APP_ADDRESS + 4))();
} }

View File

@@ -50,7 +50,7 @@ const struct usb_device_descriptor dev = {
}; };
/* I have no idea what this means. I haven't read the HID spec. */ /* I have no idea what this means. I haven't read the HID spec. */
static const u8 hid_report_descriptor[] = { static const uint8_t hid_report_descriptor[] = {
0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01, 0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03, 0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01, 0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
@@ -66,8 +66,8 @@ static const u8 hid_report_descriptor[] = {
static const struct { static const struct {
struct usb_hid_descriptor hid_descriptor; struct usb_hid_descriptor hid_descriptor;
struct { struct {
u8 bReportDescriptorType; uint8_t bReportDescriptorType;
u16 wDescriptorLength; uint16_t wDescriptorLength;
} __attribute__((packed)) hid_report; } __attribute__((packed)) hid_report;
} __attribute__((packed)) hid_function = { } __attribute__((packed)) hid_function = {
.hid_descriptor = { .hid_descriptor = {
@@ -169,9 +169,9 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int hid_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int hid_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
@@ -183,7 +183,7 @@ static int hid_control_request(usbd_device *usbd_dev, struct usb_setup_data *req
return 0; return 0;
/* Handle the HID report descriptor. */ /* Handle the HID report descriptor. */
*buf = (u8 *)hid_report_descriptor; *buf = (uint8_t *)hid_report_descriptor;
*len = sizeof(hid_report_descriptor); *len = sizeof(hid_report_descriptor);
return 1; return 1;
@@ -202,7 +202,7 @@ static void dfu_detach_complete(usbd_device *usbd_dev, struct usb_setup_data *re
scb_reset_core(); scb_reset_core();
} }
static int dfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, u16 *len, static int dfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)buf; (void)buf;
@@ -218,7 +218,7 @@ static int dfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req
} }
#endif #endif
static void hid_set_config(usbd_device *usbd_dev, u16 wValue) static void hid_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;
(void)usbd_dev; (void)usbd_dev;
@@ -276,7 +276,7 @@ void sys_tick_handler(void)
{ {
static int x = 0; static int x = 0;
static int dir = 1; static int dir = 1;
u8 buf[4] = {0, 0, 0, 0}; uint8_t buf[4] = {0, 0, 0, 0};
buf[1] = dir; buf[1] = dir;
x += dir; x += dir;

View File

@@ -32,15 +32,15 @@
#define CMD_ERASE 0x41 #define CMD_ERASE 0x41
/* We need a special large control buffer for this device: */ /* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024]; uint8_t usbd_control_buffer[1024];
static enum dfu_state usbdfu_state = STATE_DFU_IDLE; static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static struct { static struct {
u8 buf[sizeof(usbd_control_buffer)]; uint8_t buf[sizeof(usbd_control_buffer)];
u16 len; uint16_t len;
u32 addr; uint32_t addr;
u16 blocknum; uint16_t blocknum;
} prog; } prog;
const struct usb_device_descriptor dev = { const struct usb_device_descriptor dev = {
@@ -113,7 +113,7 @@ static const char *usb_strings[] = {
"@Internal Flash /0x08000000/8*001Ka,56*001Kg", "@Internal Flash /0x08000000/8*001Ka,56*001Kg",
}; };
static u8 usbdfu_getstatus(usbd_device *usbd_dev, u32 *bwPollTimeout) static uint8_t usbdfu_getstatus(usbd_device *usbd_dev, uint32_t *bwPollTimeout)
{ {
(void)usbd_dev; (void)usbd_dev;
@@ -144,20 +144,20 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
switch (prog.buf[0]) { switch (prog.buf[0]) {
case CMD_ERASE: case CMD_ERASE:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
flash_erase_page(*dat); flash_erase_page(*dat);
} }
case CMD_SETADDR: case CMD_SETADDR:
{ {
u32 *dat = (u32 *)(prog.buf + 1); uint32_t *dat = (uint32_t *)(prog.buf + 1);
prog.addr = *dat; prog.addr = *dat;
} }
} }
} else { } else {
u32 baseaddr = prog.addr + ((prog.blocknum - 2) * uint32_t baseaddr = prog.addr + ((prog.blocknum - 2) *
dfu_function.wTransferSize); dfu_function.wTransferSize);
for (i = 0; i < prog.len; i += 2) { for (i = 0; i < prog.len; i += 2) {
u16 *dat = (u16 *)(prog.buf + i); uint16_t *dat = (uint16_t *)(prog.buf + i);
flash_program_half_word(baseaddr + i, flash_program_half_word(baseaddr + i,
*dat); *dat);
} }
@@ -176,8 +176,8 @@ static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_da
} }
} }
static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
if ((req->bmRequestType & 0x7F) != 0x21) if ((req->bmRequestType & 0x7F) != 0x21)
return 0; /* Only accept class request. */ return 0; /* Only accept class request. */
@@ -208,7 +208,7 @@ static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *
/* Upload not supported for now. */ /* Upload not supported for now. */
return 0; return 0;
case DFU_GETSTATUS: { case DFU_GETSTATUS: {
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(usbd_dev, &bwPollTimeout); (*buf)[0] = usbdfu_getstatus(usbd_dev, &bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF; (*buf)[1] = bwPollTimeout & 0xFF;
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF; (*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
@@ -237,12 +237,12 @@ int main(void)
if (!gpio_get(GPIOA, GPIO10)) { if (!gpio_get(GPIOA, GPIO10)) {
/* Boot the application if it's valid. */ /* Boot the application if it's valid. */
if ((*(volatile u32 *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) { if ((*(volatile uint32_t *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address. */ /* Set vector table base address. */
SCB_VTOR = APP_ADDRESS & 0xFFFF; SCB_VTOR = APP_ADDRESS & 0xFFFF;
/* Initialise master stack pointer. */ /* Initialise master stack pointer. */
asm volatile("msr msp, %0"::"g" asm volatile("msr msp, %0"::"g"
(*(volatile u32 *)APP_ADDRESS)); (*(volatile uint32_t *)APP_ADDRESS));
/* Jump to application. */ /* Jump to application. */
(*(void (**)())(APP_ADDRESS + 4))(); (*(void (**)())(APP_ADDRESS + 4))();
} }

View File

@@ -24,7 +24,7 @@
#define USART_ECHO_EN 1 #define USART_ECHO_EN 1
#define SEND_BUFFER_SIZE 256 #define SEND_BUFFER_SIZE 256
#define FLASH_OPERATION_ADDRESS ((u32)0x0800f000) #define FLASH_OPERATION_ADDRESS ((uint32_t)0x0800f000)
#define FLASH_PAGE_NUM_MAX 127 #define FLASH_PAGE_NUM_MAX 127
#define FLASH_PAGE_SIZE 0x800 #define FLASH_PAGE_SIZE 0x800
#define FLASH_WRONG_DATA_WRITTEN 0x80 #define FLASH_WRONG_DATA_WRITTEN 0x80
@@ -34,45 +34,45 @@
static void init_system(void); static void init_system(void);
static void init_usart(void); static void init_usart(void);
/*usart operations*/ /*usart operations*/
static void usart_send_string(u32 usart, u8 *string, u16 str_size); static void usart_send_string(uint32_t usart, uint8_t *string, uint16_t str_size);
static void usart_get_string(u32 usart, u8 *string, u16 str_max_size); static void usart_get_string(uint32_t usart, uint8_t *string, uint16_t str_max_size);
/*flash operations*/ /*flash operations*/
static u32 flash_program_data(u32 start_address, u8 *input_data, u16 num_elements); static uint32_t flash_program_data(uint32_t start_address, uint8_t *input_data, uint16_t num_elements);
static void flash_read_data(u32 start_address, u16 num_elements, u8 *output_data); static void flash_read_data(uint32_t start_address, uint16_t num_elements, uint8_t *output_data);
/*local functions to work with strings*/ /*local functions to work with strings*/
static void local_ltoa_hex(u32 value, u8 *out_string); static void local_ltoa_hex(uint32_t value, uint8_t *out_string);
int main(void) int main(void)
{ {
u32 result = 0; uint32_t result = 0;
u8 str_send[SEND_BUFFER_SIZE], str_verify[SEND_BUFFER_SIZE]; uint8_t str_send[SEND_BUFFER_SIZE], str_verify[SEND_BUFFER_SIZE];
init_system(); init_system();
while(1) while(1)
{ {
usart_send_string(USART1, (u8*)"Please enter string to write into Flash memory:\n\r", SEND_BUFFER_SIZE); usart_send_string(USART1, (uint8_t*)"Please enter string to write into Flash memory:\n\r", SEND_BUFFER_SIZE);
usart_get_string(USART1, str_send, SEND_BUFFER_SIZE); usart_get_string(USART1, str_send, SEND_BUFFER_SIZE);
result = flash_program_data(FLASH_OPERATION_ADDRESS, str_send, SEND_BUFFER_SIZE); result = flash_program_data(FLASH_OPERATION_ADDRESS, str_send, SEND_BUFFER_SIZE);
switch(result) switch(result)
{ {
case RESULT_OK: /*everything ok*/ case RESULT_OK: /*everything ok*/
usart_send_string(USART1, (u8*)"Verification of written data: ", SEND_BUFFER_SIZE); usart_send_string(USART1, (uint8_t*)"Verification of written data: ", SEND_BUFFER_SIZE);
flash_read_data(FLASH_OPERATION_ADDRESS, SEND_BUFFER_SIZE, str_verify); flash_read_data(FLASH_OPERATION_ADDRESS, SEND_BUFFER_SIZE, str_verify);
usart_send_string(USART1, str_verify, SEND_BUFFER_SIZE); usart_send_string(USART1, str_verify, SEND_BUFFER_SIZE);
break; break;
case FLASH_WRONG_DATA_WRITTEN: /*data read from Flash is different than written data*/ case FLASH_WRONG_DATA_WRITTEN: /*data read from Flash is different than written data*/
usart_send_string(USART1, (u8*)"Wrong data written into flash memory", SEND_BUFFER_SIZE); usart_send_string(USART1, (uint8_t*)"Wrong data written into flash memory", SEND_BUFFER_SIZE);
break; break;
default: /*wrong flags' values in Flash Status Register (FLASH_SR)*/ default: /*wrong flags' values in Flash Status Register (FLASH_SR)*/
usart_send_string(USART1, (u8*)"Wrong value of FLASH_SR: ", SEND_BUFFER_SIZE); usart_send_string(USART1, (uint8_t*)"Wrong value of FLASH_SR: ", SEND_BUFFER_SIZE);
local_ltoa_hex(result, str_send); local_ltoa_hex(result, str_send);
usart_send_string(USART1, str_send, SEND_BUFFER_SIZE); usart_send_string(USART1, str_send, SEND_BUFFER_SIZE);
break; break;
} }
/*send end_of_line*/ /*send end_of_line*/
usart_send_string(USART1, (u8*)"\r\n", 3); usart_send_string(USART1, (uint8_t*)"\r\n", 3);
} }
return 0; return 0;
} }
@@ -100,19 +100,19 @@ static void init_usart(void)
usart_enable(USART1); usart_enable(USART1);
} }
static void usart_send_string(u32 usart, u8 *string, u16 str_size) static void usart_send_string(uint32_t usart, uint8_t *string, uint16_t str_size)
{ {
u16 iter = 0; uint16_t iter = 0;
do do
{ {
usart_send_blocking(usart, string[iter++]); usart_send_blocking(usart, string[iter++]);
}while(string[iter] != 0 && iter < str_size); }while(string[iter] != 0 && iter < str_size);
} }
static void usart_get_string(u32 usart, u8 *out_string, u16 str_max_size) static void usart_get_string(uint32_t usart, uint8_t *out_string, uint16_t str_max_size)
{ {
u8 sign = 0; uint8_t sign = 0;
u16 iter = 0; uint16_t iter = 0;
while(iter < str_max_size) while(iter < str_max_size)
{ {
@@ -127,18 +127,18 @@ static void usart_get_string(u32 usart, u8 *out_string, u16 str_max_size)
else else
{ {
out_string[iter] = 0; out_string[iter] = 0;
usart_send_string(USART1, (u8*)"\r\n", 3); usart_send_string(USART1, (uint8_t*)"\r\n", 3);
break; break;
} }
} }
} }
static u32 flash_program_data(u32 start_address, u8 *input_data, u16 num_elements) static uint32_t flash_program_data(uint32_t start_address, uint8_t *input_data, uint16_t num_elements)
{ {
u16 iter; uint16_t iter;
u32 current_address = start_address; uint32_t current_address = start_address;
u32 page_address = start_address; uint32_t page_address = start_address;
u32 flash_status = 0; uint32_t flash_status = 0;
/*check if start_address is in proper range*/ /*check if start_address is in proper range*/
if((start_address - FLASH_BASE) >= (FLASH_PAGE_SIZE * (FLASH_PAGE_NUM_MAX+1))) if((start_address - FLASH_BASE) >= (FLASH_PAGE_SIZE * (FLASH_PAGE_NUM_MAX+1)))
@@ -160,34 +160,34 @@ static u32 flash_program_data(u32 start_address, u8 *input_data, u16 num_element
for(iter=0; iter<num_elements; iter += 4) for(iter=0; iter<num_elements; iter += 4)
{ {
/*programming word data*/ /*programming word data*/
flash_program_word(current_address+iter, *((u32*)(input_data + iter))); flash_program_word(current_address+iter, *((uint32_t*)(input_data + iter)));
flash_status = flash_get_status_flags(); flash_status = flash_get_status_flags();
if(flash_status != FLASH_SR_EOP) if(flash_status != FLASH_SR_EOP)
return flash_status; return flash_status;
/*verify if correct data is programmed*/ /*verify if correct data is programmed*/
if(*((u32*)(current_address+iter)) != *((u32*)(input_data + iter))) if(*((uint32_t*)(current_address+iter)) != *((uint32_t*)(input_data + iter)))
return FLASH_WRONG_DATA_WRITTEN; return FLASH_WRONG_DATA_WRITTEN;
} }
return 0; return 0;
} }
static void flash_read_data(u32 start_address, u16 num_elements, u8 *output_data) static void flash_read_data(uint32_t start_address, uint16_t num_elements, uint8_t *output_data)
{ {
u16 iter; uint16_t iter;
u32 *memory_ptr= (u32*)start_address; uint32_t *memory_ptr= (uint32_t*)start_address;
for(iter=0; iter<num_elements/4; iter++) for(iter=0; iter<num_elements/4; iter++)
{ {
*(u32*)output_data = *(memory_ptr + iter); *(uint32_t*)output_data = *(memory_ptr + iter);
output_data += 4; output_data += 4;
} }
} }
static void local_ltoa_hex(u32 value, u8 *out_string) static void local_ltoa_hex(uint32_t value, uint8_t *out_string)
{ {
u8 iter; uint8_t iter;
/*end of string*/ /*end of string*/
out_string += 8; out_string += 8;

View File

@@ -75,10 +75,10 @@ const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int simple_control_callback(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int simple_control_callback(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)buf; (void)buf;
(void)len; (void)len;

View File

@@ -73,7 +73,7 @@ static void gpio_setup(void)
void usart2_isr(void) void usart2_isr(void)
{ {
static u8 data = 'A'; static uint8_t data = 'A';
/* Check if we were called because of RXNE. */ /* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) && if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&
@@ -106,7 +106,7 @@ void usart2_isr(void)
int main(void) int main(void)
{ {
SCB_VTOR = (u32) 0x08005000; SCB_VTOR = (uint32_t) 0x08005000;
clock_setup(); clock_setup();
gpio_setup(); gpio_setup();

View File

@@ -165,10 +165,10 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
(void)buf; (void)buf;
@@ -203,7 +203,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
return 0; return 0;
} }
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep) static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{ {
(void)ep; (void)ep;
(void)usbd_dev; (void)usbd_dev;
@@ -217,7 +217,7 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
} }
} }
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue) static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;
(void)usbd_dev; (void)usbd_dev;
@@ -239,7 +239,7 @@ int main(void)
usbd_device *usbd_dev; usbd_device *usbd_dev;
SCB_VTOR = (u32) 0x08005000; SCB_VTOR = (uint32_t) 0x08005000;
rcc_clock_setup_in_hse_8mhz_out_72mhz(); rcc_clock_setup_in_hse_8mhz_out_72mhz();

View File

@@ -124,14 +124,14 @@ static void dac_setup(void)
dac_set_trigger_source(DAC_CR_TSEL2_SW); dac_set_trigger_source(DAC_CR_TSEL2_SW);
} }
static u16 read_adc_naiive(u8 channel) static uint16_t read_adc_naiive(uint8_t channel)
{ {
u8 channel_array[16]; uint8_t channel_array[16];
channel_array[0] = channel; channel_array[0] = channel;
adc_set_regular_sequence(ADC1, 1, channel_array); adc_set_regular_sequence(ADC1, 1, channel_array);
adc_start_conversion_direct(ADC1); adc_start_conversion_direct(ADC1);
while (!adc_eoc(ADC1)); while (!adc_eoc(ADC1));
u16 reg16 = adc_read_regular(ADC1); uint16_t reg16 = adc_read_regular(ADC1);
return reg16; return reg16;
} }
@@ -148,11 +148,11 @@ int main(void)
GPIO_CNF_OUTPUT_PUSHPULL, LED_DISCOVERY_USER_PIN); GPIO_CNF_OUTPUT_PUSHPULL, LED_DISCOVERY_USER_PIN);
while (1) { while (1) {
u16 input_adc0 = read_adc_naiive(0); uint16_t input_adc0 = read_adc_naiive(0);
u16 target = input_adc0 / 2; uint16_t target = input_adc0 / 2;
dac_load_data_buffer_single(target, RIGHT12, CHANNEL_2); dac_load_data_buffer_single(target, RIGHT12, CHANNEL_2);
dac_software_trigger(CHANNEL_2); dac_software_trigger(CHANNEL_2);
u16 input_adc1 = read_adc_naiive(1); uint16_t input_adc1 = read_adc_naiive(1);
printf("tick: %d: adc0= %u, target adc1=%d, adc1=%d\n", printf("tick: %d: adc0= %u, target adc1=%d, adc1=%d\n",
j++, input_adc0, target, input_adc1); j++, input_adc0, target, input_adc1);
gpio_toggle(LED_DISCOVERY_USER_PORT, LED_DISCOVERY_USER_PIN); /* LED on/off */ gpio_toggle(LED_DISCOVERY_USER_PORT, LED_DISCOVERY_USER_PIN); /* LED on/off */

View File

@@ -21,7 +21,7 @@
#include <libopencm3/stm32/f1/rcc.h> #include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h> #include <libopencm3/stm32/f1/gpio.h>
u16 exti_line_state; uint16_t exti_line_state;
/* Set STM32 to 24 MHz. */ /* Set STM32 to 24 MHz. */
static void clock_setup(void) static void clock_setup(void)

View File

@@ -47,7 +47,7 @@ static void usart_setup(void)
// usart_set_baudrate(USART1, 38400); // usart_set_baudrate(USART1, 38400);
/* TODO usart_set_baudrate() doesn't support 24MHz clock (yet). */ /* TODO usart_set_baudrate() doesn't support 24MHz clock (yet). */
/* This is the equivalent: */ /* This is the equivalent: */
USART_BRR(USART1) = (u16)((24000000 << 4) / (38400 * 16)); USART_BRR(USART1) = (uint16_t)((24000000 << 4) / (38400 * 16));
usart_set_databits(USART1, 8); usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1); usart_set_stopbits(USART1, USART_STOPBITS_1);
@@ -76,7 +76,7 @@ static void nvic_setup(void)
void rtc_isr(void) void rtc_isr(void)
{ {
volatile u32 j = 0, c = 0; volatile uint32_t j = 0, c = 0;
/* The interrupt flag isn't cleared by hardware, we have to do it. */ /* The interrupt flag isn't cleared by hardware, we have to do it. */
rtc_clear_flag(RTC_SEC); rtc_clear_flag(RTC_SEC);

View File

@@ -43,7 +43,7 @@ static void usart_setup(void)
// usart_set_baudrate(USART1, 38400); // usart_set_baudrate(USART1, 38400);
/* TODO usart_set_baudrate() doesn't support 24MHz clock (yet). */ /* TODO usart_set_baudrate() doesn't support 24MHz clock (yet). */
/* This is the equivalent: */ /* This is the equivalent: */
USART_BRR(USART1) = (u16)((24000000 << 4) / (38400 * 16)); USART_BRR(USART1) = (uint16_t)((24000000 << 4) / (38400 * 16));
usart_set_databits(USART1, 8); usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1); usart_set_stopbits(USART1, USART_STOPBITS_1);

View File

@@ -93,7 +93,7 @@ int _write(int file, char *ptr, int len)
int main(void) int main(void)
{ {
int counter = 0; int counter = 0;
volatile u16 dummy __attribute__((unused)); volatile uint16_t dummy __attribute__((unused));
clock_setup(); clock_setup();
gpio_setup(); gpio_setup();
@@ -105,7 +105,7 @@ int main(void)
printf("Hello, world! %i\r\n", counter); printf("Hello, world! %i\r\n", counter);
/* Stops RX buffer overflow, but probably not needed. */ /* Stops RX buffer overflow, but probably not needed. */
dummy = spi_read(SPI2); dummy = spi_read(SPI2);
spi_send(SPI2, (u8) counter); spi_send(SPI2, (uint8_t) counter);
gpio_toggle(GPIOC, GPIO3); gpio_toggle(GPIOC, GPIO3);
} }

View File

@@ -22,7 +22,7 @@
#include <libopencm3/stm32/f4/rcc.h> #include <libopencm3/stm32/f4/rcc.h>
#include <libopencm3/stm32/f4/gpio.h> #include <libopencm3/stm32/f4/gpio.h>
u16 exti_line_state; uint16_t exti_line_state;
/* Set STM32 to 168 MHz. */ /* Set STM32 to 168 MHz. */
static void clock_setup(void) static void clock_setup(void)

View File

@@ -50,11 +50,11 @@ static void gpio_setup(void)
} }
/* Tried to folow the guidelines in the stm32f4 user manual.*/ /* Tried to folow the guidelines in the stm32f4 user manual.*/
static u32 random_int(void) static uint32_t random_int(void)
{ {
static u32 last_value=0; static uint32_t last_value=0;
static u32 new_value=0; static uint32_t new_value=0;
u32 error_bits = 0; uint32_t error_bits = 0;
error_bits = RNG_SR_SEIS | RNG_SR_CEIS; error_bits = RNG_SR_SEIS | RNG_SR_CEIS;
while (new_value==last_value) { while (new_value==last_value) {
/* Check for error flags and if data is ready. */ /* Check for error flags and if data is ready. */
@@ -73,7 +73,7 @@ int main(void)
gpio_setup(); gpio_setup();
rng_setup(); rng_setup();
while(1){ while(1){
u32 rnd; uint32_t rnd;
rnd = random_int(); rnd = random_int();
for(i=0;i!=32;++i){ for(i=0;i!=32;++i){
if ( (rnd & (1 << i))!=0 ) if ( (rnd & (1 << i))!=0 )

View File

@@ -86,7 +86,7 @@ int main(void)
void usart2_isr(void) void usart2_isr(void)
{ {
static u8 data = 'A'; static uint8_t data = 'A';
/* Check if we were called because of RXNE. */ /* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) && if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&

View File

@@ -165,10 +165,10 @@ static const char *usb_strings[] = {
}; };
/* Buffer to be used for control requests. */ /* Buffer to be used for control requests. */
u8 usbd_control_buffer[128]; uint8_t usbd_control_buffer[128];
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf, static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{ {
(void)complete; (void)complete;
(void)buf; (void)buf;
@@ -192,7 +192,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *
return 0; return 0;
} }
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep) static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
{ {
(void)ep; (void)ep;
@@ -207,7 +207,7 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
gpio_toggle(GPIOC, GPIO5); gpio_toggle(GPIOC, GPIO5);
} }
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue) static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue)
{ {
(void)wValue; (void)wValue;

View File

@@ -162,8 +162,8 @@ static int setup_rtc(void)
; ;
/* set synch prescaler, using defaults for 1Hz out */ /* set synch prescaler, using defaults for 1Hz out */
u32 sync = 255; uint32_t sync = 255;
u32 async = 127; uint32_t async = 127;
rtc_set_prescaler(sync, async); rtc_set_prescaler(sync, async);
/* load time and date here if desired, and hour format */ /* load time and date here if desired, and hour format */