Skip to content

Commit

Permalink
px4_micro_hal: add PX4_ARCH_DCACHE_LINESIZE definition
Browse files Browse the repository at this point in the history
  • Loading branch information
bkueng committed Oct 11, 2019
1 parent 132dcda commit 3234aca
Show file tree
Hide file tree
Showing 5 changed files with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <board_config.h>
#include <px4_config.h>
#include <px4_micro_hal.h>

#include <perf/perf_counter.h>

Expand Down Expand Up @@ -164,6 +165,6 @@ class ArchPX4IOSerial : public PX4IO_serial
/**
* IO Buffer storage
*/
static uint8_t _io_buffer_storage[] __attribute__((aligned(PX4IO_SERIAL_BUF_ALIGN)));
static uint8_t _io_buffer_storage[] __attribute__((aligned(PX4_ARCH_DCACHE_LINESIZE)));
};

Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ __BEGIN_DECLS
# define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL
#endif
#define PX4_NUMBER_I2C_BUSES STM32_NI2C
#define PX4_ARCH_DCACHE_LINESIZE 32

__END_DECLS

Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,5 @@

#pragma once

#define PX4IO_SERIAL_BUF_ALIGN 4
#include "../../../stm32_common/include/px4_arch/px4io_serial.h"

Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ __BEGIN_DECLS
#define PX4_BBSRAM_GETDESC_IOCTL STM32F7_BBSRAM_GETDESC_IOCTL
#define PX4_FLASH_BASE 0x08000000
#define PX4_NUMBER_I2C_BUSES STM32F7_NI2C
#define PX4_ARCH_DCACHE_LINESIZE ARMV7M_DCACHE_LINESIZE

void stm32_flash_lock(void);
void stm32_flash_unlock(void);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,5 @@

#pragma once

#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE
#include "../../../stm32_common/include/px4_arch/px4io_serial.h"

0 comments on commit 3234aca

Please sign in to comment.