Browse Source

px4_micro_hal: add PX4_ARCH_DCACHE_LINESIZE definition

sbg
Beat Küng 6 years ago
parent
commit
3234aca53b
  1. 3
      platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h
  2. 1
      platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h
  3. 1
      platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h
  4. 1
      platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h
  5. 1
      platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h

3
platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/px4io_serial.h

@ -41,6 +41,7 @@
#include <board_config.h> #include <board_config.h>
#include <px4_config.h> #include <px4_config.h>
#include <px4_micro_hal.h>
#include <perf/perf_counter.h> #include <perf/perf_counter.h>
@ -164,6 +165,6 @@ private:
/** /**
* IO Buffer storage * 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)));
}; };

1
platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/micro_hal.h

@ -46,6 +46,7 @@ __BEGIN_DECLS
# define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL # define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL
#endif #endif
#define PX4_NUMBER_I2C_BUSES STM32_NI2C #define PX4_NUMBER_I2C_BUSES STM32_NI2C
#define PX4_ARCH_DCACHE_LINESIZE 32
__END_DECLS __END_DECLS

1
platforms/nuttx/src/px4/stm/stm32f4/include/px4_arch/px4io_serial.h

@ -33,6 +33,5 @@
#pragma once #pragma once
#define PX4IO_SERIAL_BUF_ALIGN 4
#include "../../../stm32_common/include/px4_arch/px4io_serial.h" #include "../../../stm32_common/include/px4_arch/px4io_serial.h"

1
platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/micro_hal.h

@ -46,6 +46,7 @@ __BEGIN_DECLS
#define PX4_BBSRAM_GETDESC_IOCTL STM32F7_BBSRAM_GETDESC_IOCTL #define PX4_BBSRAM_GETDESC_IOCTL STM32F7_BBSRAM_GETDESC_IOCTL
#define PX4_FLASH_BASE 0x08000000 #define PX4_FLASH_BASE 0x08000000
#define PX4_NUMBER_I2C_BUSES STM32F7_NI2C #define PX4_NUMBER_I2C_BUSES STM32F7_NI2C
#define PX4_ARCH_DCACHE_LINESIZE ARMV7M_DCACHE_LINESIZE
void stm32_flash_lock(void); void stm32_flash_lock(void);
void stm32_flash_unlock(void); void stm32_flash_unlock(void);

1
platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/px4io_serial.h

@ -33,6 +33,5 @@
#pragma once #pragma once
#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE
#include "../../../stm32_common/include/px4_arch/px4io_serial.h" #include "../../../stm32_common/include/px4_arch/px4io_serial.h"

Loading…
Cancel
Save