From ab43a83bed7cd6f69820c42e684450d130c57f98 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 23 Aug 2019 16:04:22 +0200 Subject: [PATCH] platform: restructure (NuttX) architecture-specific code updated: tone_alarm, px4io_serial, px4_micro_hal --- CMakeLists.txt | 12 ++ boards/airmind/mindpx-v2/default.cmake | 1 - boards/auav/x21/default.cmake | 1 - boards/av/x-v1/default.cmake | 1 - boards/holybro/kakutef7/default.cmake | 1 - boards/mro/ctrl-zero-f7/default.cmake | 1 - boards/nxp/fmuk66-v3/default.cmake | 1 - boards/omnibus/f4sd/default.cmake | 1 - boards/px4/fmu-v2/default.cmake | 1 - boards/px4/fmu-v2/fixedwing.cmake | 1 - boards/px4/fmu-v2/lpe.cmake | 1 - boards/px4/fmu-v2/multicopter.cmake | 1 - boards/px4/fmu-v2/rover.cmake | 1 - boards/px4/fmu-v2/test.cmake | 1 - boards/px4/fmu-v3/default.cmake | 1 - boards/px4/fmu-v3/rtps.cmake | 1 - boards/px4/fmu-v3/stackcheck.cmake | 1 - boards/px4/fmu-v4/default.cmake | 1 - boards/px4/fmu-v4/rtps.cmake | 1 - boards/px4/fmu-v4/stackcheck.cmake | 1 - boards/px4/fmu-v4pro/default.cmake | 1 - boards/px4/fmu-v4pro/rtps.cmake | 1 - boards/px4/fmu-v5/critmonitor.cmake | 1 - boards/px4/fmu-v5/default.cmake | 1 - boards/px4/fmu-v5/fixedwing.cmake | 1 - boards/px4/fmu-v5/irqmonitor.cmake | 1 - boards/px4/fmu-v5/multicopter.cmake | 1 - boards/px4/fmu-v5/rover.cmake | 1 - boards/px4/fmu-v5/rtps.cmake | 1 - boards/px4/fmu-v5/stackcheck.cmake | 1 - boards/px4/fmu-v5x/default.cmake | 1 - boards/px4/fmu-v5x/fixedwing.cmake | 1 - boards/px4/fmu-v5x/multicopter.cmake | 1 - boards/px4/fmu-v5x/rover.cmake | 1 - boards/px4/fmu-v5x/rtps.cmake | 1 - boards/px4/fmu-v5x/stackcheck.cmake | 1 - boards/px4/sitl/default.cmake | 1 - boards/px4/sitl/rtps.cmake | 1 - boards/px4/sitl/test.cmake | 1 - boards/uvify/core/default.cmake | 1 - cmake/px4_add_board.cmake | 3 + cmake/px4_add_common_flags.cmake | 1 + cmake/px4_add_library.cmake | 2 +- platforms/nuttx/CMakeLists.txt | 2 - platforms/nuttx/cmake/px4_impl_os.cmake | 33 +++ platforms/nuttx/src/px4/CMakeLists.txt | 37 ++++ .../{px4_layer => px4/common}/CMakeLists.txt | 0 .../common}/console_buffer.cpp | 0 .../{px4_layer => px4/common}/px4_init.cpp | 0 .../common}/px4_nuttx_impl.cpp | 0 .../common}/px4_nuttx_tasks.c | 0 .../src/px4/common/px4_platform_micro_hal.h | 56 +++++ platforms/nuttx/src/px4/nxp/CMakeLists.txt | 36 ++++ .../px4/nxp/common}/tone_alarm/CMakeLists.txt | 2 +- .../common}/tone_alarm/ToneAlarmInterface.cpp | 10 +- .../nuttx/src/px4/nxp/kinetis/CMakeLists.txt | 38 ++++ .../src/px4/nxp/kinetis/px4_arch_micro_hal.h | 112 ++++++++++ platforms/nuttx/src/px4/stm/CMakeLists.txt | 36 ++++ .../px4/stm/stm32_common/px4_arch_micro_hal.h | 105 ++++++++++ .../px4io_serial/arch_px4io_serial.h | 113 +--------- .../stm32_common}/tone_alarm/CMakeLists.txt | 2 +- .../tone_alarm/ToneAlarmInterface.cpp | 0 .../tone_alarm/ToneAlarmInterfaceGPIO.cpp | 11 +- .../tone_alarm/ToneAlarmInterfacePWM.cpp | 11 +- .../nuttx/src/px4/stm/stm32f1/CMakeLists.txt | 36 ++++ .../nuttx/src/px4/stm/stm32f1/io_timer.h | 37 ++++ .../src/px4/stm/stm32f1/px4_arch_micro_hal.h | 51 +++++ .../nuttx/src/px4/stm/stm32f4/CMakeLists.txt | 38 ++++ .../src/px4/stm/stm32f4/px4_arch_micro_hal.h | 51 +++++ .../stm/stm32f4/px4io_serial/CMakeLists.txt | 36 ++++ .../stm32f4/px4io_serial/arch_px4io_serial.h | 38 ++++ .../stm/stm32f4/px4io_serial/px4io_serial.cpp | 35 ++-- .../nuttx/src/px4/stm/stm32f7/CMakeLists.txt | 38 ++++ .../src/px4/stm/stm32f7/px4_arch_micro_hal.h | 55 +++++ .../stm/stm32f7/px4io_serial/CMakeLists.txt | 36 ++++ .../stm32f7/px4io_serial/arch_px4io_serial.h | 38 ++++ .../stm/stm32f7/px4io_serial/px4io_serial.cpp | 33 ++- platforms/posix/cmake/px4_impl_os.cmake | 18 ++ platforms/posix/src/px4/CMakeLists.txt | 37 ++++ .../src/px4/common}/CMakeLists.txt | 3 +- .../common/include/px4_platform/micro_hal.h | 36 ++++ .../posix/src/px4/generic/CMakeLists.txt | 36 ++++ .../src/px4/generic/generic/CMakeLists.txt | 36 ++++ .../generic/include/px4_arch/micro_hal.h | 36 ++++ .../generic}/tone_alarm/CMakeLists.txt | 2 +- .../tone_alarm/ToneAlarmInterface.cpp | 14 +- platforms/posix/src/px4/px4/CMakeLists.txt | 36 ++++ platforms/qurt/CMakeLists.txt | 2 - platforms/qurt/cmake/px4_impl_os.cmake | 18 ++ platforms/qurt/src/px4/CMakeLists.txt | 37 ++++ .../{px4_layer => px4/common}/CMakeLists.txt | 6 +- .../{px4_layer => px4/common}/commands_hil.c | 0 .../{px4_layer => px4/common}/get_commands.h | 0 .../common/include/px4_platform/micro_hal.h | 36 ++++ .../src/{px4_layer => px4/common}/lib_crc32.c | 0 .../src/{px4_layer => px4/common}/main.cpp | 0 .../{px4_layer => px4/common}/px4_init.cpp | 0 .../common}/px4_qurt_impl.cpp | 0 .../common}/px4_qurt_tasks.cpp | 0 .../{px4_layer => px4/common}/qurt_stubs.c | 0 .../{px4_layer => px4/common}/shmem_qurt.cpp | 0 platforms/qurt/src/px4/common/stubs/posix.c | 159 ++++++++++++++ platforms/qurt/src/px4/common/stubs/qurt.c | 64 ++++++ platforms/qurt/src/px4/generic/CMakeLists.txt | 36 ++++ .../{ => px4/generic/generic}/CMakeLists.txt | 5 +- .../generic/include/px4_arch/micro_hal.h | 36 ++++ src/drivers/px4io/CMakeLists.txt | 5 +- src/drivers/px4io/px4io_serial.cpp | 4 +- src/drivers/tone_alarm/CMakeLists.txt | 2 +- src/modules/px4iofirmware/CMakeLists.txt | 3 +- src/platforms/px4_micro_hal.h | 194 +----------------- 111 files changed, 1640 insertions(+), 404 deletions(-) create mode 100644 platforms/nuttx/src/px4/CMakeLists.txt rename platforms/nuttx/src/{px4_layer => px4/common}/CMakeLists.txt (100%) rename platforms/nuttx/src/{px4_layer => px4/common}/console_buffer.cpp (100%) rename platforms/nuttx/src/{px4_layer => px4/common}/px4_init.cpp (100%) rename platforms/nuttx/src/{px4_layer => px4/common}/px4_nuttx_impl.cpp (100%) rename platforms/nuttx/src/{px4_layer => px4/common}/px4_nuttx_tasks.c (100%) create mode 100644 platforms/nuttx/src/px4/common/px4_platform_micro_hal.h create mode 100644 platforms/nuttx/src/px4/nxp/CMakeLists.txt rename {src/drivers/stm32 => platforms/nuttx/src/px4/nxp/common}/tone_alarm/CMakeLists.txt (97%) rename {src/drivers/kinetis => platforms/nuttx/src/px4/nxp/common}/tone_alarm/ToneAlarmInterface.cpp (98%) create mode 100644 platforms/nuttx/src/px4/nxp/kinetis/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/nxp/kinetis/px4_arch_micro_hal.h create mode 100644 platforms/nuttx/src/px4/stm/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32_common/px4_arch_micro_hal.h rename src/drivers/px4io/px4io_serial.h => platforms/nuttx/src/px4/stm/stm32_common/px4io_serial/arch_px4io_serial.h (65%) rename {src/drivers/sim => platforms/nuttx/src/px4/stm/stm32_common}/tone_alarm/CMakeLists.txt (97%) rename {src/drivers/stm32 => platforms/nuttx/src/px4/stm/stm32_common}/tone_alarm/ToneAlarmInterface.cpp (100%) rename {src/drivers/stm32 => platforms/nuttx/src/px4/stm/stm32_common}/tone_alarm/ToneAlarmInterfaceGPIO.cpp (93%) rename {src/drivers/stm32 => platforms/nuttx/src/px4/stm/stm32_common}/tone_alarm/ToneAlarmInterfacePWM.cpp (98%) create mode 100644 platforms/nuttx/src/px4/stm/stm32f1/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32f1/io_timer.h create mode 100644 platforms/nuttx/src/px4/stm/stm32f1/px4_arch_micro_hal.h create mode 100644 platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32f4/px4_arch_micro_hal.h create mode 100644 platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/arch_px4io_serial.h rename src/drivers/px4io/px4io_serial_f4.cpp => platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp (93%) create mode 100644 platforms/nuttx/src/px4/stm/stm32f7/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32f7/px4_arch_micro_hal.h create mode 100644 platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/arch_px4io_serial.h rename src/drivers/px4io/px4io_serial_f7.cpp => platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp (94%) create mode 100644 platforms/posix/src/px4/CMakeLists.txt rename platforms/{nuttx/src => posix/src/px4/common}/CMakeLists.txt (94%) create mode 100644 platforms/posix/src/px4/common/include/px4_platform/micro_hal.h create mode 100644 platforms/posix/src/px4/generic/CMakeLists.txt create mode 100644 platforms/posix/src/px4/generic/generic/CMakeLists.txt create mode 100644 platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h rename {src/drivers/kinetis => platforms/posix/src/px4/generic/generic}/tone_alarm/CMakeLists.txt (97%) rename {src/drivers/sim => platforms/posix/src/px4/generic/generic}/tone_alarm/ToneAlarmInterface.cpp (91%) create mode 100644 platforms/posix/src/px4/px4/CMakeLists.txt create mode 100644 platforms/qurt/src/px4/CMakeLists.txt rename platforms/qurt/src/{px4_layer => px4/common}/CMakeLists.txt (96%) rename platforms/qurt/src/{px4_layer => px4/common}/commands_hil.c (100%) rename platforms/qurt/src/{px4_layer => px4/common}/get_commands.h (100%) create mode 100644 platforms/qurt/src/px4/common/include/px4_platform/micro_hal.h rename platforms/qurt/src/{px4_layer => px4/common}/lib_crc32.c (100%) rename platforms/qurt/src/{px4_layer => px4/common}/main.cpp (100%) rename platforms/qurt/src/{px4_layer => px4/common}/px4_init.cpp (100%) rename platforms/qurt/src/{px4_layer => px4/common}/px4_qurt_impl.cpp (100%) rename platforms/qurt/src/{px4_layer => px4/common}/px4_qurt_tasks.cpp (100%) rename platforms/qurt/src/{px4_layer => px4/common}/qurt_stubs.c (100%) rename platforms/qurt/src/{px4_layer => px4/common}/shmem_qurt.cpp (100%) create mode 100644 platforms/qurt/src/px4/common/stubs/posix.c create mode 100644 platforms/qurt/src/px4/common/stubs/qurt.c create mode 100644 platforms/qurt/src/px4/generic/CMakeLists.txt rename platforms/qurt/src/{ => px4/generic/generic}/CMakeLists.txt (94%) create mode 100644 platforms/qurt/src/px4/generic/generic/include/px4_arch/micro_hal.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 1446279e15..27726052d1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -347,6 +347,17 @@ else() px4_find_python_module(jinja2 REQUIRED) endif() +#============================================================================= +# get chip and chip manufacturer +# +px4_os_determine_build_chip() +if(NOT PX4_CHIP_MANUFACTURER) + message(FATAL_ERROR "px4_os_determine_build_chip() needs to set PX4_CHIP_MANUFACTURER") +endif() +if(NOT PX4_CHIP) + message(FATAL_ERROR "px4_os_determine_build_chip() needs to set PX4_CHIP") +endif() + #============================================================================= # build flags # @@ -451,6 +462,7 @@ add_library(parameters_interface INTERFACE) include(px4_add_library) add_subdirectory(src/lib EXCLUDE_FROM_ALL) +add_subdirectory(platforms/${PX4_PLATFORM}/src/px4) add_subdirectory(src/platforms EXCLUDE_FROM_ALL) add_subdirectory(src/modules/uORB EXCLUDE_FROM_ALL) # TODO: platform layer add_subdirectory(src/drivers/boards EXCLUDE_FROM_ALL) diff --git a/boards/airmind/mindpx-v2/default.cmake b/boards/airmind/mindpx-v2/default.cmake index 82d7eeb9ee..5810b40e49 100644 --- a/boards/airmind/mindpx-v2/default.cmake +++ b/boards/airmind/mindpx-v2/default.cmake @@ -42,7 +42,6 @@ px4_add_board( rc_input stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/auav/x21/default.cmake b/boards/auav/x21/default.cmake index caa3130eb0..571f248bf2 100644 --- a/boards/auav/x21/default.cmake +++ b/boards/auav/x21/default.cmake @@ -48,7 +48,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/av/x-v1/default.cmake b/boards/av/x-v1/default.cmake index 243d3f3367..70266bc4ef 100644 --- a/boards/av/x-v1/default.cmake +++ b/boards/av/x-v1/default.cmake @@ -49,7 +49,6 @@ px4_add_board( #roboclaw stm32 stm32/adc - #stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/holybro/kakutef7/default.cmake b/boards/holybro/kakutef7/default.cmake index 393316ea07..96ece5dd2c 100644 --- a/boards/holybro/kakutef7/default.cmake +++ b/boards/holybro/kakutef7/default.cmake @@ -27,7 +27,6 @@ px4_add_board( rc_input stm32 stm32/adc - stm32/tone_alarm telemetry tone_alarm osd diff --git a/boards/mro/ctrl-zero-f7/default.cmake b/boards/mro/ctrl-zero-f7/default.cmake index 26dfedb27c..b34a0030c1 100644 --- a/boards/mro/ctrl-zero-f7/default.cmake +++ b/boards/mro/ctrl-zero-f7/default.cmake @@ -51,7 +51,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/nxp/fmuk66-v3/default.cmake b/boards/nxp/fmuk66-v3/default.cmake index 247087e455..1375a15361 100644 --- a/boards/nxp/fmuk66-v3/default.cmake +++ b/boards/nxp/fmuk66-v3/default.cmake @@ -32,7 +32,6 @@ px4_add_board( irlock kinetis kinetis/adc - kinetis/tone_alarm lights/blinkm lights/oreoled lights/rgbled diff --git a/boards/omnibus/f4sd/default.cmake b/boards/omnibus/f4sd/default.cmake index c65758e929..11ae144d4b 100644 --- a/boards/omnibus/f4sd/default.cmake +++ b/boards/omnibus/f4sd/default.cmake @@ -37,7 +37,6 @@ px4_add_board( rc_input stm32 stm32/adc - #stm32/tone_alarm #tap_esc #telemetry # all available telemetry drivers telemetry/frsky_telemetry diff --git a/boards/px4/fmu-v2/default.cmake b/boards/px4/fmu-v2/default.cmake index b218dcb38f..6199cb35e1 100644 --- a/boards/px4/fmu-v2/default.cmake +++ b/boards/px4/fmu-v2/default.cmake @@ -57,7 +57,6 @@ px4_add_board( #roboclaw stm32 stm32/adc - stm32/tone_alarm #tap_esc #telemetry # all available telemetry drivers #test_ppm diff --git a/boards/px4/fmu-v2/fixedwing.cmake b/boards/px4/fmu-v2/fixedwing.cmake index 5af5a9db9a..0feea6c54f 100644 --- a/boards/px4/fmu-v2/fixedwing.cmake +++ b/boards/px4/fmu-v2/fixedwing.cmake @@ -37,7 +37,6 @@ px4_add_board( px4io stm32 stm32/adc - stm32/tone_alarm #telemetry # all available telemetry drivers telemetry/iridiumsbd tone_alarm diff --git a/boards/px4/fmu-v2/lpe.cmake b/boards/px4/fmu-v2/lpe.cmake index 3100902268..d6637c9bec 100644 --- a/boards/px4/fmu-v2/lpe.cmake +++ b/boards/px4/fmu-v2/lpe.cmake @@ -53,7 +53,6 @@ px4_add_board( px4io stm32 stm32/adc - stm32/tone_alarm #tap_esc #telemetry # all available telemetry drivers #test_ppm diff --git a/boards/px4/fmu-v2/multicopter.cmake b/boards/px4/fmu-v2/multicopter.cmake index 4fb16fdf4c..292ec97239 100644 --- a/boards/px4/fmu-v2/multicopter.cmake +++ b/boards/px4/fmu-v2/multicopter.cmake @@ -37,7 +37,6 @@ px4_add_board( px4io stm32 stm32/adc - stm32/tone_alarm tone_alarm MODULES diff --git a/boards/px4/fmu-v2/rover.cmake b/boards/px4/fmu-v2/rover.cmake index 36290de0cf..d1b88384dd 100644 --- a/boards/px4/fmu-v2/rover.cmake +++ b/boards/px4/fmu-v2/rover.cmake @@ -33,7 +33,6 @@ px4_add_board( px4io stm32 stm32/adc - stm32/tone_alarm tone_alarm MODULES diff --git a/boards/px4/fmu-v2/test.cmake b/boards/px4/fmu-v2/test.cmake index 39b89893c8..990cc4fc05 100644 --- a/boards/px4/fmu-v2/test.cmake +++ b/boards/px4/fmu-v2/test.cmake @@ -53,7 +53,6 @@ px4_add_board( px4io stm32 stm32/adc - stm32/tone_alarm #tap_esc #telemetry # all available telemetry drivers #test_ppm diff --git a/boards/px4/fmu-v3/default.cmake b/boards/px4/fmu-v3/default.cmake index 05e87e5e96..e000342ec1 100644 --- a/boards/px4/fmu-v3/default.cmake +++ b/boards/px4/fmu-v3/default.cmake @@ -56,7 +56,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v3/rtps.cmake b/boards/px4/fmu-v3/rtps.cmake index c08515a298..92ab8850a0 100644 --- a/boards/px4/fmu-v3/rtps.cmake +++ b/boards/px4/fmu-v3/rtps.cmake @@ -55,7 +55,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v3/stackcheck.cmake b/boards/px4/fmu-v3/stackcheck.cmake index 4ff91eb9b0..914e683e80 100644 --- a/boards/px4/fmu-v3/stackcheck.cmake +++ b/boards/px4/fmu-v3/stackcheck.cmake @@ -55,7 +55,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v4/default.cmake b/boards/px4/fmu-v4/default.cmake index 04cbea663d..4af53c6efe 100644 --- a/boards/px4/fmu-v4/default.cmake +++ b/boards/px4/fmu-v4/default.cmake @@ -41,7 +41,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v4/rtps.cmake b/boards/px4/fmu-v4/rtps.cmake index b9c5968540..c14eeb5e73 100644 --- a/boards/px4/fmu-v4/rtps.cmake +++ b/boards/px4/fmu-v4/rtps.cmake @@ -43,7 +43,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v4/stackcheck.cmake b/boards/px4/fmu-v4/stackcheck.cmake index 0427e928d5..932db95cb2 100644 --- a/boards/px4/fmu-v4/stackcheck.cmake +++ b/boards/px4/fmu-v4/stackcheck.cmake @@ -41,7 +41,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v4pro/default.cmake b/boards/px4/fmu-v4pro/default.cmake index e229eb12d6..47fd9c8147 100644 --- a/boards/px4/fmu-v4pro/default.cmake +++ b/boards/px4/fmu-v4pro/default.cmake @@ -54,7 +54,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v4pro/rtps.cmake b/boards/px4/fmu-v4pro/rtps.cmake index 0de0625ea6..fdd85ea0dc 100644 --- a/boards/px4/fmu-v4pro/rtps.cmake +++ b/boards/px4/fmu-v4pro/rtps.cmake @@ -53,7 +53,6 @@ px4_add_board( roboclaw stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5/critmonitor.cmake b/boards/px4/fmu-v5/critmonitor.cmake index 5bb06eee4f..3d4c6ceac2 100644 --- a/boards/px4/fmu-v5/critmonitor.cmake +++ b/boards/px4/fmu-v5/critmonitor.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5/default.cmake b/boards/px4/fmu-v5/default.cmake index 97b9c79586..f80390d755 100644 --- a/boards/px4/fmu-v5/default.cmake +++ b/boards/px4/fmu-v5/default.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5/fixedwing.cmake b/boards/px4/fmu-v5/fixedwing.cmake index 7f5fb493f0..191563f2bf 100644 --- a/boards/px4/fmu-v5/fixedwing.cmake +++ b/boards/px4/fmu-v5/fixedwing.cmake @@ -39,7 +39,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm telemetry # all available telemetry drivers tone_alarm uavcan diff --git a/boards/px4/fmu-v5/irqmonitor.cmake b/boards/px4/fmu-v5/irqmonitor.cmake index 664d493931..9c781feb9a 100644 --- a/boards/px4/fmu-v5/irqmonitor.cmake +++ b/boards/px4/fmu-v5/irqmonitor.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5/multicopter.cmake b/boards/px4/fmu-v5/multicopter.cmake index 6b0bce74ce..f5a08a9f78 100644 --- a/boards/px4/fmu-v5/multicopter.cmake +++ b/boards/px4/fmu-v5/multicopter.cmake @@ -43,7 +43,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers tone_alarm diff --git a/boards/px4/fmu-v5/rover.cmake b/boards/px4/fmu-v5/rover.cmake index f72467f4e7..9796832670 100644 --- a/boards/px4/fmu-v5/rover.cmake +++ b/boards/px4/fmu-v5/rover.cmake @@ -43,7 +43,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm telemetry # all available telemetry drivers tone_alarm uavcan diff --git a/boards/px4/fmu-v5/rtps.cmake b/boards/px4/fmu-v5/rtps.cmake index 6f337e4c36..d0e0d8afeb 100644 --- a/boards/px4/fmu-v5/rtps.cmake +++ b/boards/px4/fmu-v5/rtps.cmake @@ -53,7 +53,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5/stackcheck.cmake b/boards/px4/fmu-v5/stackcheck.cmake index 1335d2b863..a6fa414d8d 100644 --- a/boards/px4/fmu-v5/stackcheck.cmake +++ b/boards/px4/fmu-v5/stackcheck.cmake @@ -53,7 +53,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5x/default.cmake b/boards/px4/fmu-v5x/default.cmake index 3bab45afd2..2da260fbce 100644 --- a/boards/px4/fmu-v5x/default.cmake +++ b/boards/px4/fmu-v5x/default.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5x/fixedwing.cmake b/boards/px4/fmu-v5x/fixedwing.cmake index 436f509c8d..135ea9974a 100644 --- a/boards/px4/fmu-v5x/fixedwing.cmake +++ b/boards/px4/fmu-v5x/fixedwing.cmake @@ -49,7 +49,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm telemetry # all available telemetry drivers tone_alarm uavcan diff --git a/boards/px4/fmu-v5x/multicopter.cmake b/boards/px4/fmu-v5x/multicopter.cmake index 46fdec308e..8579b2f8e9 100644 --- a/boards/px4/fmu-v5x/multicopter.cmake +++ b/boards/px4/fmu-v5x/multicopter.cmake @@ -50,7 +50,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers tone_alarm diff --git a/boards/px4/fmu-v5x/rover.cmake b/boards/px4/fmu-v5x/rover.cmake index dd6a4186c6..a1a02e552b 100644 --- a/boards/px4/fmu-v5x/rover.cmake +++ b/boards/px4/fmu-v5x/rover.cmake @@ -53,7 +53,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm telemetry # all available telemetry drivers tone_alarm uavcan diff --git a/boards/px4/fmu-v5x/rtps.cmake b/boards/px4/fmu-v5x/rtps.cmake index f69c8bdc2e..c0b81368db 100644 --- a/boards/px4/fmu-v5x/rtps.cmake +++ b/boards/px4/fmu-v5x/rtps.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/fmu-v5x/stackcheck.cmake b/boards/px4/fmu-v5x/stackcheck.cmake index 8264d38d8d..3e0e37e56f 100644 --- a/boards/px4/fmu-v5x/stackcheck.cmake +++ b/boards/px4/fmu-v5x/stackcheck.cmake @@ -55,7 +55,6 @@ px4_add_board( safety_button stm32 stm32/adc - stm32/tone_alarm tap_esc telemetry # all available telemetry drivers test_ppm diff --git a/boards/px4/sitl/default.cmake b/boards/px4/sitl/default.cmake index ed04be1010..ed7aa3f81e 100644 --- a/boards/px4/sitl/default.cmake +++ b/boards/px4/sitl/default.cmake @@ -17,7 +17,6 @@ px4_add_board( #magnetometer # all available magnetometer drivers pwm_out_sim #telemetry # all available telemetry drivers - sim/tone_alarm tone_alarm #uavcan diff --git a/boards/px4/sitl/rtps.cmake b/boards/px4/sitl/rtps.cmake index 0832820bcc..e5437c565d 100644 --- a/boards/px4/sitl/rtps.cmake +++ b/boards/px4/sitl/rtps.cmake @@ -17,7 +17,6 @@ px4_add_board( #magnetometer # all available magnetometer drivers pwm_out_sim #telemetry # all available telemetry drivers - sim/tone_alarm tone_alarm #uavcan diff --git a/boards/px4/sitl/test.cmake b/boards/px4/sitl/test.cmake index 3fc12e8755..bb66117394 100644 --- a/boards/px4/sitl/test.cmake +++ b/boards/px4/sitl/test.cmake @@ -17,7 +17,6 @@ px4_add_board( #magnetometer # all available magnetometer drivers pwm_out_sim #telemetry # all available telemetry drivers - sim/tone_alarm tone_alarm #uavcan diff --git a/boards/uvify/core/default.cmake b/boards/uvify/core/default.cmake index 6b50d55c88..1c889cf4ac 100644 --- a/boards/uvify/core/default.cmake +++ b/boards/uvify/core/default.cmake @@ -47,7 +47,6 @@ px4_add_board( rc_input stm32 stm32/adc - stm32/tone_alarm #tap_esc telemetry # all available telemetry drivers #test_ppm diff --git a/cmake/px4_add_board.cmake b/cmake/px4_add_board.cmake index 80d9435034..bc9cb85669 100644 --- a/cmake/px4_add_board.cmake +++ b/cmake/px4_add_board.cmake @@ -183,6 +183,9 @@ function(px4_add_board) set(PX4_PLATFORM ${PLATFORM} CACHE STRING "PX4 board OS" FORCE) list(APPEND CMAKE_MODULE_PATH ${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/cmake) + # platform-specific include path + include_directories(${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/src/px4/common/include) + if(ARCHITECTURE) set(CMAKE_SYSTEM_PROCESSOR ${ARCHITECTURE} CACHE INTERNAL "system processor" FORCE) endif() diff --git a/cmake/px4_add_common_flags.cmake b/cmake/px4_add_common_flags.cmake index 032503da38..9d8f722c38 100644 --- a/cmake/px4_add_common_flags.cmake +++ b/cmake/px4_add_common_flags.cmake @@ -174,6 +174,7 @@ function(px4_add_common_flags) ${PX4_BINARY_DIR}/src/lib ${PX4_BINARY_DIR}/src/modules + ${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/src/px4/${PX4_CHIP_MANUFACTURER}/${PX4_CHIP} ${PX4_SOURCE_DIR}/src ${PX4_SOURCE_DIR}/src/include ${PX4_SOURCE_DIR}/src/lib diff --git a/cmake/px4_add_library.cmake b/cmake/px4_add_library.cmake index a7290fd482..2a6377c71a 100644 --- a/cmake/px4_add_library.cmake +++ b/cmake/px4_add_library.cmake @@ -40,7 +40,7 @@ include(px4_base) # Like add_library but with PX4 platform dependencies # function(px4_add_library target) - add_library(${target} ${ARGN}) + add_library(${target} EXCLUDE_FROM_ALL ${ARGN}) target_compile_definitions(${target} PRIVATE MODULE_NAME="${target}") diff --git a/platforms/nuttx/CMakeLists.txt b/platforms/nuttx/CMakeLists.txt index 574526535c..d8ca630b0a 100644 --- a/platforms/nuttx/CMakeLists.txt +++ b/platforms/nuttx/CMakeLists.txt @@ -36,8 +36,6 @@ include(cygwin_cygpath) set(NUTTX_DIR ${PX4_BINARY_DIR}/NuttX/nuttx) set(NUTTX_APPS_DIR ${PX4_BINARY_DIR}/NuttX/apps) -add_subdirectory(src) - add_executable(px4 ${PX4_SOURCE_DIR}/src/platforms/empty.c) set(FW_NAME ${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.elf) set_target_properties(px4 PROPERTIES OUTPUT_NAME ${FW_NAME}) diff --git a/platforms/nuttx/cmake/px4_impl_os.cmake b/platforms/nuttx/cmake/px4_impl_os.cmake index 3c9b27ef58..34cd7bb32f 100644 --- a/platforms/nuttx/cmake/px4_impl_os.cmake +++ b/platforms/nuttx/cmake/px4_impl_os.cmake @@ -38,6 +38,7 @@ # Required OS Interface Functions # # * px4_os_add_flags +# * px4_os_determine_build_chip # * px4_os_prebuild_targets # @@ -84,6 +85,38 @@ function(px4_os_add_flags) endfunction() +#============================================================================= +# +# px4_os_determine_build_chip +# +# Sets PX4_CHIP and PX4_CHIP_MANUFACTURER. +# +# Usage: +# px4_os_determine_build_chip() +# +function(px4_os_determine_build_chip) + + # determine chip and chip manufacturer based on NuttX config + if (CONFIG_STM32_STM32F10XX) + set(CHIP_MANUFACTURER "stm") + set(CHIP "stm32f1") + elseif(CONFIG_STM32_STM32F4XXX) + set(CHIP_MANUFACTURER "stm") + set(CHIP "stm32f4") + elseif(CONFIG_ARCH_CHIP_STM32F7) + set(CHIP_MANUFACTURER "stm") + set(CHIP "stm32f7") + elseif(CONFIG_ARCH_CHIP_MK66FN2M0VMD18) + set(CHIP_MANUFACTURER "nxp") + set(CHIP "k66") + else() + message(FATAL_ERROR "Could not determine chip architecture from NuttX config. You may have to add it.") + endif() + + set(PX4_CHIP ${CHIP} CACHE STRING "PX4 Chip" FORCE) + set(PX4_CHIP_MANUFACTURER ${CHIP_MANUFACTURER} CACHE STRING "PX4 Chip Manufacturer" FORCE) +endfunction() + #============================================================================= # # px4_os_prebuild_targets diff --git a/platforms/nuttx/src/px4/CMakeLists.txt b/platforms/nuttx/src/px4/CMakeLists.txt new file mode 100644 index 0000000000..929788b587 --- /dev/null +++ b/platforms/nuttx/src/px4/CMakeLists.txt @@ -0,0 +1,37 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(common) + +add_subdirectory(${PX4_CHIP_MANUFACTURER}) + diff --git a/platforms/nuttx/src/px4_layer/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt similarity index 100% rename from platforms/nuttx/src/px4_layer/CMakeLists.txt rename to platforms/nuttx/src/px4/common/CMakeLists.txt diff --git a/platforms/nuttx/src/px4_layer/console_buffer.cpp b/platforms/nuttx/src/px4/common/console_buffer.cpp similarity index 100% rename from platforms/nuttx/src/px4_layer/console_buffer.cpp rename to platforms/nuttx/src/px4/common/console_buffer.cpp diff --git a/platforms/nuttx/src/px4_layer/px4_init.cpp b/platforms/nuttx/src/px4/common/px4_init.cpp similarity index 100% rename from platforms/nuttx/src/px4_layer/px4_init.cpp rename to platforms/nuttx/src/px4/common/px4_init.cpp diff --git a/platforms/nuttx/src/px4_layer/px4_nuttx_impl.cpp b/platforms/nuttx/src/px4/common/px4_nuttx_impl.cpp similarity index 100% rename from platforms/nuttx/src/px4_layer/px4_nuttx_impl.cpp rename to platforms/nuttx/src/px4/common/px4_nuttx_impl.cpp diff --git a/platforms/nuttx/src/px4_layer/px4_nuttx_tasks.c b/platforms/nuttx/src/px4/common/px4_nuttx_tasks.c similarity index 100% rename from platforms/nuttx/src/px4_layer/px4_nuttx_tasks.c rename to platforms/nuttx/src/px4/common/px4_nuttx_tasks.c diff --git a/platforms/nuttx/src/px4/common/px4_platform_micro_hal.h b/platforms/nuttx/src/px4/common/px4_platform_micro_hal.h new file mode 100644 index 0000000000..8bf62a5f8d --- /dev/null +++ b/platforms/nuttx/src/px4/common/px4_platform_micro_hal.h @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +__BEGIN_DECLS +#include +#include + +/* For historical reasons (NuttX STM32 numbering) PX4 bus numbering is 1 based + * All PX4 code, including, board code is written to assuming 1 based numbering. + * The following macros are used to allow the board config to define the bus + * numbers in terms of the NuttX driver numbering. 1,2,3 for one based numbering + * schemes or 0,1,2 for zero based schemes. + */ + +#define PX4_BUS_NUMBER_TO_PX4(x) ((x)+PX4_BUS_OFFSET) /* Use to define Zero based to match Nuttx Driver but provide 1 based to PX4 */ +#define PX4_BUS_NUMBER_FROM_PX4(x) ((x)-PX4_BUS_OFFSET) /* Use to map PX4 1 based to NuttX driver 0 based */ + +#define px4_enter_critical_section() enter_critical_section() +#define px4_leave_critical_section(flags) leave_critical_section(flags) + +#include + +__END_DECLS + diff --git a/platforms/nuttx/src/px4/nxp/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/CMakeLists.txt new file mode 100644 index 0000000000..ec489bf559 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(${PX4_CHIP}) + diff --git a/src/drivers/stm32/tone_alarm/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/common/tone_alarm/CMakeLists.txt similarity index 97% rename from src/drivers/stm32/tone_alarm/CMakeLists.txt rename to platforms/nuttx/src/px4/nxp/common/tone_alarm/CMakeLists.txt index 5251d3910a..a2d2f8144b 100644 --- a/src/drivers/stm32/tone_alarm/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/common/tone_alarm/CMakeLists.txt @@ -31,6 +31,6 @@ # ############################################################################ -px4_add_library(tone_alarm_interface +px4_add_library(arch_tone_alarm ToneAlarmInterface.cpp ) diff --git a/src/drivers/kinetis/tone_alarm/ToneAlarmInterface.cpp b/platforms/nuttx/src/px4/nxp/common/tone_alarm/ToneAlarmInterface.cpp similarity index 98% rename from src/drivers/kinetis/tone_alarm/ToneAlarmInterface.cpp rename to platforms/nuttx/src/px4/nxp/common/tone_alarm/ToneAlarmInterface.cpp index e7f36bd2ab..1090305abe 100644 --- a/src/drivers/kinetis/tone_alarm/ToneAlarmInterface.cpp +++ b/platforms/nuttx/src/px4/nxp/common/tone_alarm/ToneAlarmInterface.cpp @@ -115,7 +115,9 @@ # define rCNSC CAT3(rC, TONE_ALARM_CHANNEL, SC) /* Channel Status and Control Register used by Tone alarm */ # define STATUS CAT3(TPM_STATUS_CH, TONE_ALARM_CHANNEL, F) /* Capture and Compare Status Register used by Tone alarm */ -void ToneAlarmInterface::init() +namespace ToneAlarmInterface +{ +void init() { #ifdef GPIO_TONE_ALARM_NEG px4_arch_configgpio(GPIO_TONE_ALARM_NEG); @@ -157,7 +159,7 @@ void ToneAlarmInterface::init() rMOD = 0; // Default the timer to a modulo value of 1; playing notes will change this. } -void ToneAlarmInterface::start_note(unsigned frequency) +void start_note(unsigned frequency) { // Calculate the signal switching period. // (Signal switching period is one half of the frequency period). @@ -174,7 +176,7 @@ void ToneAlarmInterface::start_note(unsigned frequency) px4_arch_configgpio(GPIO_TONE_ALARM); } -void ToneAlarmInterface::stop_note() +void stop_note() { // Stop the current note. rSC &= ~TPM_SC_CMOD_MASK; @@ -182,3 +184,5 @@ void ToneAlarmInterface::stop_note() // Ensure the GPIO is not driving the speaker. px4_arch_configgpio(GPIO_TONE_ALARM_IDLE); } + +} /* namespace ToneAlarmInterface */ diff --git a/platforms/nuttx/src/px4/nxp/kinetis/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/kinetis/CMakeLists.txt new file mode 100644 index 0000000000..a8fba883a4 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/kinetis/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(../common/tone_alarm tone_alarm) + + + diff --git a/platforms/nuttx/src/px4/nxp/kinetis/px4_arch_micro_hal.h b/platforms/nuttx/src/px4/nxp/kinetis/px4_arch_micro_hal.h new file mode 100644 index 0000000000..fd8eb7adb5 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/kinetis/px4_arch_micro_hal.h @@ -0,0 +1,112 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../common/px4_platform_micro_hal.h" + +__BEGIN_DECLS + +#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_KINETISK66 + +// Fixme: using ?? +#define PX4_BBSRAM_SIZE 2048 +#define PX4_BBSRAM_GETDESC_IOCTL 0 +#define PX4_NUMBER_I2C_BUSES KINETIS_NI2C + +#define GPIO_OUTPUT_SET GPIO_OUTPUT_ONE +#define GPIO_OUTPUT_CLEAR GPIO_OUTPUT_ZERO + +#include +#include +#include +#include + +/* Kinetis defines the 128 bit UUID as + * init32_t[4] that can be read as words + * init32_t[0] PX4_CPU_UUID_ADDRESS[0] bits 127:96 (offset 0) + * init32_t[1] PX4_CPU_UUID_ADDRESS[1] bits 95:64 (offset 4) + * init32_t[2] PX4_CPU_UUID_ADDRESS[1] bits 63:32 (offset 8) + * init32_t[3] PX4_CPU_UUID_ADDRESS[3] bits 31:0 (offset C) + * + * PX4 uses the words in bigendian order MSB to LSB + * word [0] [1] [2] [3] + * bits 127:96 95-64 63-32, 31-00, + */ +#define PX4_CPU_UUID_BYTE_LENGTH KINETIS_UID_SIZE +#define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t)) + +/* The mfguid will be an array of bytes with + * MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1 + * + * It will be converted to a string with the MSD on left and LSD on the right most position. + */ +#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH + +/* define common formating across all commands */ + +#define PX4_CPU_UUID_WORD32_FORMAT "%08x" +#define PX4_CPU_UUID_WORD32_SEPARATOR ":" + +#define PX4_CPU_UUID_WORD32_UNIQUE_H 3 /* Least significant digits change the most */ +#define PX4_CPU_UUID_WORD32_UNIQUE_M 2 /* Middle High significant digits */ +#define PX4_CPU_UUID_WORD32_UNIQUE_L 1 /* Middle Low significant digits */ +#define PX4_CPU_UUID_WORD32_UNIQUE_N 0 /* Most significant digits change the least */ + +/* Separator nnn:nnn:nnnn 2 char per byte term */ +#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1) +#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1) + +#define kinetis_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet + +#define px4_savepanic(fileno, context, length) kinetis_bbsram_savepanic(fileno, context, length) + +/* bus_num is zero based on kinetis and must be translated from the legacy one based */ + +#define PX4_BUS_OFFSET 1 /* Kinetis buses are 0 based and adjustment is needed */ + +#define px4_spibus_initialize(bus_num_1based) kinetis_spibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based)) + +#define px4_i2cbus_initialize(bus_num_1based) kinetis_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based)) +#define px4_i2cbus_uninitialize(pdev) kinetis_i2cbus_uninitialize(pdev) + +#define px4_arch_configgpio(pinset) kinetis_pinconfig(pinset) +#define px4_arch_unconfiggpio(pinset) +#define px4_arch_gpioread(pinset) kinetis_gpioread(pinset) +#define px4_arch_gpiowrite(pinset, value) kinetis_gpiowrite(pinset, value) + +/* kinetis_gpiosetevent is not implemented and will need to be added */ + +#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) kinetis_gpiosetevent(pinset,r,f,e,fp,a) + +__END_DECLS diff --git a/platforms/nuttx/src/px4/stm/CMakeLists.txt b/platforms/nuttx/src/px4/stm/CMakeLists.txt new file mode 100644 index 0000000000..ec489bf559 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(${PX4_CHIP}) + diff --git a/platforms/nuttx/src/px4/stm/stm32_common/px4_arch_micro_hal.h b/platforms/nuttx/src/px4/stm/stm32_common/px4_arch_micro_hal.h new file mode 100644 index 0000000000..2f01b48f27 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32_common/px4_arch_micro_hal.h @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + +#include "../../common/px4_platform_micro_hal.h" + +__BEGIN_DECLS + +#include +#include +#include + +/* STM32/32F7 defines the 96 bit UUID as + * init32_t[3] that can be read as bytes/half-words/words + * init32_t[0] PX4_CPU_UUID_ADDRESS[0] bits 31:0 (offset 0) + * init32_t[1] PX4_CPU_UUID_ADDRESS[1] bits 63:32 (offset 4) + * init32_t[2] PX4_CPU_UUID_ADDRESS[3] bits 96:64 (offset 8) + * + * The original PX4 stm32 (legacy) based implementation **displayed** the + * UUID as: ABCD EFGH IJKL + * Where: + * A was bit 31 and D was bit 0 + * E was bit 63 and H was bit 32 + * I was bit 95 and L was bit 64 + * + * Since the string was used by some manufactures to identify the units + * it must be preserved. + * + * For new targets moving forward we will use + * IJKL EFGH ABCD + */ +#define PX4_CPU_UUID_BYTE_LENGTH 12 +#define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t)) + +/* The mfguid will be an array of bytes with + * MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1 + * + * It will be converted to a string with the MSD on left and LSD on the right most position. + */ +#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH + +/* By not defining PX4_CPU_UUID_CORRECT_CORRELATION the following maintains the legacy incorrect order + * used for selection of significant digits of the UUID in the PX4 code base. + * This is done to avoid the ripple effects changing the IDs used on STM32 base platforms + */ +#if defined(PX4_CPU_UUID_CORRECT_CORRELATION) +# define PX4_CPU_UUID_WORD32_UNIQUE_H 0 /* Least significant digits change the most */ +# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */ +# define PX4_CPU_UUID_WORD32_UNIQUE_L 2 /* Most significant digits change the least */ +#else +/* Legacy incorrect ordering */ +# define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */ +# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */ +# define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */ +#endif + +/* Separator nnn:nnn:nnnn 2 char per byte term */ +#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1) +#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1) + +#define px4_savepanic(fileno, context, length) stm32_bbsram_savepanic(fileno, context, length) + +#define PX4_BUS_OFFSET 0 /* STM buses are 1 based no adjustment needed */ +#define px4_spibus_initialize(bus_num_1based) stm32_spibus_initialize(bus_num_1based) + +#define px4_i2cbus_initialize(bus_num_1based) stm32_i2cbus_initialize(bus_num_1based) +#define px4_i2cbus_uninitialize(pdev) stm32_i2cbus_uninitialize(pdev) + +#define px4_arch_configgpio(pinset) stm32_configgpio(pinset) +#define px4_arch_unconfiggpio(pinset) stm32_unconfiggpio(pinset) +#define px4_arch_gpioread(pinset) stm32_gpioread(pinset) +#define px4_arch_gpiowrite(pinset, value) stm32_gpiowrite(pinset, value) +#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) stm32_gpiosetevent(pinset,r,f,e,fp,a) + +__END_DECLS diff --git a/src/drivers/px4io/px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32_common/px4io_serial/arch_px4io_serial.h similarity index 65% rename from src/drivers/px4io/px4io_serial.h rename to platforms/nuttx/src/px4/stm/stm32_common/px4io_serial/arch_px4io_serial.h index 8e17606da6..7d72d65dbb 100644 --- a/src/drivers/px4io/px4io_serial.h +++ b/platforms/nuttx/src/px4/stm/stm32_common/px4io_serial/arch_px4io_serial.h @@ -32,31 +32,17 @@ ****************************************************************************/ /** - * @file px4io_driver.h + * @file arch_px4io_serial.h * - * Interface for PX4IO + * Serial Interface definition for PX4IO */ #pragma once -/* XXX trim includes */ -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - #include +#include + +#include #include #include @@ -117,87 +103,17 @@ private: PX4IO_serial &operator = (const PX4IO_serial &); }; -#if defined(CONFIG_STM32_STM32F10XX) || defined(CONFIG_STM32_STM32F4XXX) -/** XXX use F4 implementation for F1 as well. **/ - -#define PX4IO_INTERFACE_CLASS PX4IO_serial_f4 -#define PX4IO_INTERFACE_F4 - -class PX4IO_serial_f4 : public PX4IO_serial -{ -public: - PX4IO_serial_f4(); - ~PX4IO_serial_f4(); - - virtual int init(); - virtual int ioctl(unsigned operation, unsigned &arg); - -protected: - /** - * Start the transaction with IO and wait for it to complete. - */ - int _bus_exchange(IOPacket *_packet); - -private: - DMA_HANDLE _tx_dma; - DMA_HANDLE _rx_dma; - - IOPacket *_current_packet; - - /** saved DMA status */ - static const unsigned _dma_status_inactive = 0x80000000; // low bits overlap DMA_STATUS_* values - static const unsigned _dma_status_waiting = 0x00000000; - volatile unsigned _rx_dma_status; - - /** client-waiting lock/signal */ - px4_sem_t _completion_semaphore; - - /** - * DMA completion handler. - */ - static void _dma_callback(DMA_HANDLE handle, uint8_t status, void *arg); - void _do_rx_dma_callback(unsigned status); - - /** - * Serial interrupt handler. - */ - static int _interrupt(int vector, void *context, void *arg); - void _do_interrupt(); - - /** - * Cancel any DMA in progress with an error. - */ - void _abort_dma(); - - /** - * Performance counters. - */ - perf_counter_t _pc_dmasetup; - perf_counter_t _pc_dmaerrs; - - /* do not allow top copying this class */ - PX4IO_serial_f4(PX4IO_serial_f4 &); - PX4IO_serial_f4 &operator = (const PX4IO_serial_f4 &); - - /** - * IO Buffer storage - */ - static IOPacket _io_buffer_storage; // XXX static to ensure DMA-able memory -}; - -#elif defined(CONFIG_ARCH_CHIP_STM32F7) - -#define PX4IO_INTERFACE_CLASS PX4IO_serial_f7 -#define PX4IO_INTERFACE_F7 #include -class PX4IO_serial_f7 : public PX4IO_serial +class ArchPX4IOSerial : public PX4IO_serial { public: - PX4IO_serial_f7(); - ~PX4IO_serial_f7(); + ArchPX4IOSerial(); + ArchPX4IOSerial(ArchPX4IOSerial &) = delete; + ArchPX4IOSerial &operator = (const ArchPX4IOSerial &) = delete; + ~ArchPX4IOSerial(); virtual int init(); virtual int ioctl(unsigned operation, unsigned &arg); @@ -245,16 +161,9 @@ private: perf_counter_t _pc_dmasetup; perf_counter_t _pc_dmaerrs; - /* do not allow top copying this class */ - PX4IO_serial_f7(PX4IO_serial_f7 &); - PX4IO_serial_f7 &operator = (const PX4IO_serial_f7 &); - /** * IO Buffer storage */ - static uint8_t _io_buffer_storage[] __attribute__((aligned(ARMV7M_DCACHE_LINESIZE))); + static uint8_t _io_buffer_storage[] __attribute__((aligned(PX4IO_SERIAL_BUF_ALIGN))); }; -#else -#error "Interface not implemented for this chip" -#endif diff --git a/src/drivers/sim/tone_alarm/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/CMakeLists.txt similarity index 97% rename from src/drivers/sim/tone_alarm/CMakeLists.txt rename to platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/CMakeLists.txt index 5251d3910a..a2d2f8144b 100644 --- a/src/drivers/sim/tone_alarm/CMakeLists.txt +++ b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/CMakeLists.txt @@ -31,6 +31,6 @@ # ############################################################################ -px4_add_library(tone_alarm_interface +px4_add_library(arch_tone_alarm ToneAlarmInterface.cpp ) diff --git a/src/drivers/stm32/tone_alarm/ToneAlarmInterface.cpp b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterface.cpp similarity index 100% rename from src/drivers/stm32/tone_alarm/ToneAlarmInterface.cpp rename to platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterface.cpp diff --git a/src/drivers/stm32/tone_alarm/ToneAlarmInterfaceGPIO.cpp b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfaceGPIO.cpp similarity index 93% rename from src/drivers/stm32/tone_alarm/ToneAlarmInterfaceGPIO.cpp rename to platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfaceGPIO.cpp index c73a512963..eb5f6a342c 100644 --- a/src/drivers/stm32/tone_alarm/ToneAlarmInterfaceGPIO.cpp +++ b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfaceGPIO.cpp @@ -35,19 +35,24 @@ #include #include -void ToneAlarmInterface::init() +namespace ToneAlarmInterface +{ + +void init() { // Configure the GPIO to the idle state. px4_arch_configgpio(GPIO_TONE_ALARM_IDLE); } -void ToneAlarmInterface::start_note(unsigned frequency) +void start_note(unsigned frequency) { px4_arch_gpiowrite(GPIO_TONE_ALARM_GPIO, 1); } -void ToneAlarmInterface::stop_note() +void stop_note() { // Stop the current note. px4_arch_gpiowrite(GPIO_TONE_ALARM_GPIO, 0); } + +} /* namespace ToneAlarmInterface */ diff --git a/src/drivers/stm32/tone_alarm/ToneAlarmInterfacePWM.cpp b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp similarity index 98% rename from src/drivers/stm32/tone_alarm/ToneAlarmInterfacePWM.cpp rename to platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp index eb72700a0a..6073068ee6 100644 --- a/src/drivers/stm32/tone_alarm/ToneAlarmInterfacePWM.cpp +++ b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp @@ -219,7 +219,10 @@ # define rSR REG(STM32_GTIM_SR_OFFSET) #endif -void ToneAlarmInterface::init() +namespace ToneAlarmInterface +{ + +void init() { #ifdef GPIO_TONE_ALARM_NEG px4_arch_configgpio(GPIO_TONE_ALARM_NEG); @@ -251,7 +254,7 @@ void ToneAlarmInterface::init() rCR1 = GTIM_CR1_CEN; // Ensure the timer is running. } -void ToneAlarmInterface::start_note(unsigned frequency) +void start_note(unsigned frequency) { // Calculate the signal switching period. // (Signal switching period is one half of the frequency period). @@ -276,7 +279,7 @@ void ToneAlarmInterface::start_note(unsigned frequency) px4_arch_configgpio(GPIO_TONE_ALARM); } -void ToneAlarmInterface::stop_note() +void stop_note() { // Stop the current note. rCCER &= ~TONE_CCER; @@ -284,3 +287,5 @@ void ToneAlarmInterface::stop_note() // Ensure the GPIO is not driving the speaker. px4_arch_configgpio(GPIO_TONE_ALARM_IDLE); } + +} /* namespace ToneAlarmInterface */ diff --git a/platforms/nuttx/src/px4/stm/stm32f1/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f1/CMakeLists.txt new file mode 100644 index 0000000000..9ca45d87a9 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f1/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(../stm32_common/io_pins io_pins) + diff --git a/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h b/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h new file mode 100644 index 0000000000..2960835d2e --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f1/io_timer.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../stm32_common/include/px4_arch/io_timer.h" + diff --git a/platforms/nuttx/src/px4/stm/stm32f1/px4_arch_micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f1/px4_arch_micro_hal.h new file mode 100644 index 0000000000..1e5beb9206 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f1/px4_arch_micro_hal.h @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../stm32_common/px4_arch_micro_hal.h" + +__BEGIN_DECLS + +#include +#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F4 +#define PX4_FLASH_BASE STM32_FLASH_BASE +#if defined(CONFIG_STM32_STM32F4XXX) +# include +# define PX4_BBSRAM_SIZE STM32_BBSRAM_SIZE +# define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL +#endif +#define PX4_NUMBER_I2C_BUSES STM32_NI2C + +__END_DECLS + diff --git a/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt new file mode 100644 index 0000000000..7e389b99e9 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(../stm32_common/tone_alarm tone_alarm) + +add_subdirectory(px4io_serial) + diff --git a/platforms/nuttx/src/px4/stm/stm32f4/px4_arch_micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f4/px4_arch_micro_hal.h new file mode 100644 index 0000000000..1e5beb9206 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4_arch_micro_hal.h @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../stm32_common/px4_arch_micro_hal.h" + +__BEGIN_DECLS + +#include +#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F4 +#define PX4_FLASH_BASE STM32_FLASH_BASE +#if defined(CONFIG_STM32_STM32F4XXX) +# include +# define PX4_BBSRAM_SIZE STM32_BBSRAM_SIZE +# define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL +#endif +#define PX4_NUMBER_I2C_BUSES STM32_NI2C + +__END_DECLS + diff --git a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/CMakeLists.txt new file mode 100644 index 0000000000..df450593b1 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2015-2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(arch_px4io_serial + px4io_serial.cpp +) diff --git a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/arch_px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/arch_px4io_serial.h new file mode 100644 index 0000000000..fb1f5c8dae --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/arch_px4io_serial.h @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#define PX4IO_SERIAL_BUF_ALIGN 4 +#include "../stm32_common/px4io_serial/arch_px4io_serial.h" + diff --git a/src/drivers/px4io/px4io_serial_f4.cpp b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp similarity index 93% rename from src/drivers/px4io/px4io_serial_f4.cpp rename to platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp index 8ada27f0a1..6b186f8a3c 100644 --- a/src/drivers/px4io/px4io_serial_f4.cpp +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp @@ -32,14 +32,12 @@ ****************************************************************************/ /** - * @file px4io_serial_f4.cpp + * @file px4io_serial.cpp * * Serial interface for PX4IO on STM32F4 */ -#include "px4io_serial.h" - -#ifdef PX4IO_INTERFACE_F4 +#include "arch_px4io_serial.h" /* serial register accessors */ #define REG(_x) (*(volatile uint32_t *)(PX4IO_SERIAL_BASE + _x)) @@ -51,9 +49,9 @@ #define rCR3 REG(STM32_USART_CR3_OFFSET) #define rGTPR REG(STM32_USART_GTPR_OFFSET) -IOPacket PX4IO_serial_f4::_io_buffer_storage; +uint8_t ArchPX4IOSerial::_io_buffer_storage[sizeof(IOPacket)]; -PX4IO_serial_f4::PX4IO_serial_f4() : +ArchPX4IOSerial::ArchPX4IOSerial() : _tx_dma(nullptr), _rx_dma(nullptr), _current_packet(nullptr), @@ -69,7 +67,7 @@ PX4IO_serial_f4::PX4IO_serial_f4() : { } -PX4IO_serial_f4::~PX4IO_serial_f4() +ArchPX4IOSerial::~ArchPX4IOSerial() { if (_tx_dma != nullptr) { stm32_dmastop(_tx_dma); @@ -105,12 +103,12 @@ PX4IO_serial_f4::~PX4IO_serial_f4() } int -PX4IO_serial_f4::init() +ArchPX4IOSerial::init() { /* initialize base implementation */ int r; - if ((r = PX4IO_serial::init(&_io_buffer_storage)) != 0) { + if ((r = PX4IO_serial::init((IOPacket *)&_io_buffer_storage[0])) != 0) { return r; } @@ -167,7 +165,7 @@ PX4IO_serial_f4::init() } int -PX4IO_serial_f4::ioctl(unsigned operation, unsigned &arg) +ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg) { switch (operation) { @@ -232,7 +230,7 @@ PX4IO_serial_f4::ioctl(unsigned operation, unsigned &arg) } int -PX4IO_serial_f4::_bus_exchange(IOPacket *_packet) +ArchPX4IOSerial::_bus_exchange(IOPacket *_packet) { _current_packet = _packet; @@ -351,17 +349,17 @@ PX4IO_serial_f4::_bus_exchange(IOPacket *_packet) } void -PX4IO_serial_f4::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) +ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) { if (arg != nullptr) { - PX4IO_serial_f4 *ps = reinterpret_cast(arg); + ArchPX4IOSerial *ps = reinterpret_cast(arg); ps->_do_rx_dma_callback(status); } } void -PX4IO_serial_f4::_do_rx_dma_callback(unsigned status) +ArchPX4IOSerial::_do_rx_dma_callback(unsigned status) { /* on completion of a reply, wake the waiter */ if (_rx_dma_status == _dma_status_waiting) { @@ -386,10 +384,10 @@ PX4IO_serial_f4::_do_rx_dma_callback(unsigned status) } int -PX4IO_serial_f4::_interrupt(int irq, void *context, void *arg) +ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) { if (arg != nullptr) { - PX4IO_serial_f4 *instance = reinterpret_cast(arg); + ArchPX4IOSerial *instance = reinterpret_cast(arg); instance->_do_interrupt(); } @@ -398,7 +396,7 @@ PX4IO_serial_f4::_interrupt(int irq, void *context, void *arg) } void -PX4IO_serial_f4::_do_interrupt() +ArchPX4IOSerial::_do_interrupt() { uint32_t sr = rSR; /* get UART status register */ (void)rDR; /* read DR to clear status */ @@ -458,7 +456,7 @@ PX4IO_serial_f4::_do_interrupt() } void -PX4IO_serial_f4::_abort_dma() +ArchPX4IOSerial::_abort_dma() { /* disable UART DMA */ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR); @@ -471,4 +469,3 @@ PX4IO_serial_f4::_abort_dma() stm32_dmastop(_rx_dma); } -#endif /* PX4IO_INTERFACE_F4 */ diff --git a/platforms/nuttx/src/px4/stm/stm32f7/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f7/CMakeLists.txt new file mode 100644 index 0000000000..7e389b99e9 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/CMakeLists.txt @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(../stm32_common/tone_alarm tone_alarm) + +add_subdirectory(px4io_serial) + diff --git a/platforms/nuttx/src/px4/stm/stm32f7/px4_arch_micro_hal.h b/platforms/nuttx/src/px4/stm/stm32f7/px4_arch_micro_hal.h new file mode 100644 index 0000000000..ff2eb0d5d3 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/px4_arch_micro_hal.h @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../stm32_common/px4_arch_micro_hal.h" + +__BEGIN_DECLS + +#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F7 +#include +#include +#include //include up_systemreset() which is included on stm32.h +#include +#define PX4_BBSRAM_SIZE STM32F7_BBSRAM_SIZE +#define PX4_BBSRAM_GETDESC_IOCTL STM32F7_BBSRAM_GETDESC_IOCTL +#define PX4_FLASH_BASE 0x08000000 +#define PX4_NUMBER_I2C_BUSES STM32F7_NI2C + +void stm32_flash_lock(void); +void stm32_flash_unlock(void); +int stm32_flash_writeprotect(size_t page, bool enabled); + +__END_DECLS + diff --git a/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/CMakeLists.txt b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/CMakeLists.txt new file mode 100644 index 0000000000..df450593b1 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2015-2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(arch_px4io_serial + px4io_serial.cpp +) diff --git a/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/arch_px4io_serial.h b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/arch_px4io_serial.h new file mode 100644 index 0000000000..4528e75174 --- /dev/null +++ b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/arch_px4io_serial.h @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#define PX4IO_SERIAL_BUF_ALIGN ARMV7M_DCACHE_LINESIZE +#include "../stm32_common/px4io_serial/arch_px4io_serial.h" + diff --git a/src/drivers/px4io/px4io_serial_f7.cpp b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp similarity index 94% rename from src/drivers/px4io/px4io_serial_f7.cpp rename to platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp index bcaa38f471..03e3ee0963 100644 --- a/src/drivers/px4io/px4io_serial_f7.cpp +++ b/platforms/nuttx/src/px4/stm/stm32f7/px4io_serial/px4io_serial.cpp @@ -32,14 +32,12 @@ ****************************************************************************/ /** - * @file px4io_serial_f7.cpp + * @file px4io_serial.cpp * * Serial interface for PX4IO on STM32F7 */ -#include "px4io_serial.h" - -#ifdef PX4IO_INTERFACE_F7 +#include "arch_px4io_serial.h" #include "stm32_uart.h" #include @@ -60,9 +58,9 @@ #define DMA_BUFFER_MASK (ARMV7M_DCACHE_LINESIZE - 1) #define DMA_ALIGN_UP(n) (((n) + DMA_BUFFER_MASK) & ~DMA_BUFFER_MASK) -uint8_t PX4IO_serial_f7::_io_buffer_storage[DMA_ALIGN_UP(sizeof(IOPacket))]; +uint8_t ArchPX4IOSerial::_io_buffer_storage[DMA_ALIGN_UP(sizeof(IOPacket))]; -PX4IO_serial_f7::PX4IO_serial_f7() : +ArchPX4IOSerial::ArchPX4IOSerial() : _tx_dma(nullptr), _rx_dma(nullptr), _current_packet(nullptr), @@ -78,7 +76,7 @@ PX4IO_serial_f7::PX4IO_serial_f7() : { } -PX4IO_serial_f7::~PX4IO_serial_f7() +ArchPX4IOSerial::~ArchPX4IOSerial() { if (_tx_dma != nullptr) { stm32_dmastop(_tx_dma); @@ -114,7 +112,7 @@ PX4IO_serial_f7::~PX4IO_serial_f7() } int -PX4IO_serial_f7::init() +ArchPX4IOSerial::init() { /* initialize base implementation */ int r = PX4IO_serial::init((IOPacket *)&_io_buffer_storage[0]); @@ -178,7 +176,7 @@ PX4IO_serial_f7::init() } int -PX4IO_serial_f7::ioctl(unsigned operation, unsigned &arg) +ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg) { switch (operation) { @@ -243,7 +241,7 @@ PX4IO_serial_f7::ioctl(unsigned operation, unsigned &arg) } int -PX4IO_serial_f7::_bus_exchange(IOPacket *_packet) +ArchPX4IOSerial::_bus_exchange(IOPacket *_packet) { _current_packet = _packet; @@ -369,17 +367,17 @@ PX4IO_serial_f7::_bus_exchange(IOPacket *_packet) } void -PX4IO_serial_f7::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) +ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) { if (arg != nullptr) { - PX4IO_serial_f7 *ps = reinterpret_cast(arg); + ArchPX4IOSerial *ps = reinterpret_cast(arg); ps->_do_rx_dma_callback(status); } } void -PX4IO_serial_f7::_do_rx_dma_callback(unsigned status) +ArchPX4IOSerial::_do_rx_dma_callback(unsigned status) { /* on completion of a reply, wake the waiter */ if (_rx_dma_status == _dma_status_waiting) { @@ -405,10 +403,10 @@ PX4IO_serial_f7::_do_rx_dma_callback(unsigned status) } int -PX4IO_serial_f7::_interrupt(int irq, void *context, void *arg) +ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) { if (arg != nullptr) { - PX4IO_serial_f7 *instance = reinterpret_cast(arg); + ArchPX4IOSerial *instance = reinterpret_cast(arg); instance->_do_interrupt(); } @@ -417,7 +415,7 @@ PX4IO_serial_f7::_interrupt(int irq, void *context, void *arg) } void -PX4IO_serial_f7::_do_interrupt() +ArchPX4IOSerial::_do_interrupt() { uint32_t sr = rISR; /* get UART status register */ @@ -485,7 +483,7 @@ PX4IO_serial_f7::_do_interrupt() } void -PX4IO_serial_f7::_abort_dma() +ArchPX4IOSerial::_abort_dma() { /* stop DMA */ stm32_dmastop(_tx_dma); @@ -502,4 +500,3 @@ PX4IO_serial_f7::_abort_dma() rICR = rISR & rISR_ERR_FLAGS_MASK; /* clear the flags */ } -#endif /* PX4IO_INTERFACE_F7 */ diff --git a/platforms/posix/cmake/px4_impl_os.cmake b/platforms/posix/cmake/px4_impl_os.cmake index da86c70ce8..ed650df2a8 100644 --- a/platforms/posix/cmake/px4_impl_os.cmake +++ b/platforms/posix/cmake/px4_impl_os.cmake @@ -42,6 +42,7 @@ # Required OS Interface Functions # # * px4_os_add_flags +# * px4_os_determine_build_chip # * px4_os_prebuild_targets # @@ -325,6 +326,23 @@ function(px4_os_add_flags) endfunction() +#============================================================================= +# +# px4_os_determine_build_chip +# +# Sets PX4_CHIP and PX4_CHIP_MANUFACTURER. +# +# Usage: +# px4_os_determine_build_chip() +# +function(px4_os_determine_build_chip) + + # always use generic chip and chip manufacturer + set(PX4_CHIP "generic" CACHE STRING "PX4 Chip" FORCE) + set(PX4_CHIP_MANUFACTURER "generic" CACHE STRING "PX4 Chip Manufacturer" FORCE) + +endfunction() + #============================================================================= # # px4_os_prebuild_targets diff --git a/platforms/posix/src/px4/CMakeLists.txt b/platforms/posix/src/px4/CMakeLists.txt new file mode 100644 index 0000000000..929788b587 --- /dev/null +++ b/platforms/posix/src/px4/CMakeLists.txt @@ -0,0 +1,37 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(common) + +add_subdirectory(${PX4_CHIP_MANUFACTURER}) + diff --git a/platforms/nuttx/src/CMakeLists.txt b/platforms/posix/src/px4/common/CMakeLists.txt similarity index 94% rename from platforms/nuttx/src/CMakeLists.txt rename to platforms/posix/src/px4/common/CMakeLists.txt index 602b1b7107..ae8401900e 100644 --- a/platforms/nuttx/src/CMakeLists.txt +++ b/platforms/posix/src/px4/common/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2019 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -31,4 +31,3 @@ # ############################################################################ -add_subdirectory(px4_layer) diff --git a/platforms/posix/src/px4/common/include/px4_platform/micro_hal.h b/platforms/posix/src/px4/common/include/px4_platform/micro_hal.h new file mode 100644 index 0000000000..a629cda2f9 --- /dev/null +++ b/platforms/posix/src/px4/common/include/px4_platform/micro_hal.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + + diff --git a/platforms/posix/src/px4/generic/CMakeLists.txt b/platforms/posix/src/px4/generic/CMakeLists.txt new file mode 100644 index 0000000000..ec489bf559 --- /dev/null +++ b/platforms/posix/src/px4/generic/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(${PX4_CHIP}) + diff --git a/platforms/posix/src/px4/generic/generic/CMakeLists.txt b/platforms/posix/src/px4/generic/generic/CMakeLists.txt new file mode 100644 index 0000000000..4db79a429f --- /dev/null +++ b/platforms/posix/src/px4/generic/generic/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(tone_alarm) + diff --git a/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h b/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h new file mode 100644 index 0000000000..d09b73c687 --- /dev/null +++ b/platforms/posix/src/px4/generic/generic/include/px4_arch/micro_hal.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + +#include + diff --git a/src/drivers/kinetis/tone_alarm/CMakeLists.txt b/platforms/posix/src/px4/generic/generic/tone_alarm/CMakeLists.txt similarity index 97% rename from src/drivers/kinetis/tone_alarm/CMakeLists.txt rename to platforms/posix/src/px4/generic/generic/tone_alarm/CMakeLists.txt index 5251d3910a..a2d2f8144b 100644 --- a/src/drivers/kinetis/tone_alarm/CMakeLists.txt +++ b/platforms/posix/src/px4/generic/generic/tone_alarm/CMakeLists.txt @@ -31,6 +31,6 @@ # ############################################################################ -px4_add_library(tone_alarm_interface +px4_add_library(arch_tone_alarm ToneAlarmInterface.cpp ) diff --git a/src/drivers/sim/tone_alarm/ToneAlarmInterface.cpp b/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp similarity index 91% rename from src/drivers/sim/tone_alarm/ToneAlarmInterface.cpp rename to platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp index 7e25fc774f..c56fb8c45f 100644 --- a/src/drivers/sim/tone_alarm/ToneAlarmInterface.cpp +++ b/platforms/posix/src/px4/generic/generic/tone_alarm/ToneAlarmInterface.cpp @@ -35,20 +35,26 @@ * @file ToneAlarmInterface.cpp */ -#include +#include #include -void ToneAlarmInterface::init() +namespace ToneAlarmInterface +{ + +void init() { // Nothing to be done in simulation. } -void ToneAlarmInterface::start_note(unsigned frequency) +void start_note(unsigned frequency) { // Nothing to be done in simulation. } -void ToneAlarmInterface::stop_note() +void stop_note() { // Nothing to be done in simulation. } + +} /* namespace ToneAlarmInterface */ + diff --git a/platforms/posix/src/px4/px4/CMakeLists.txt b/platforms/posix/src/px4/px4/CMakeLists.txt new file mode 100644 index 0000000000..ec489bf559 --- /dev/null +++ b/platforms/posix/src/px4/px4/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(${PX4_CHIP}) + diff --git a/platforms/qurt/CMakeLists.txt b/platforms/qurt/CMakeLists.txt index 3c17462dd7..1885d1078f 100644 --- a/platforms/qurt/CMakeLists.txt +++ b/platforms/qurt/CMakeLists.txt @@ -5,8 +5,6 @@ include(fastrpc) include(qurt_lib) include(qurt_flags) -add_subdirectory(src) - include_directories(${CMAKE_CURRENT_BINARY_DIR}) get_property(module_libraries GLOBAL PROPERTY PX4_MODULE_LIBRARIES) diff --git a/platforms/qurt/cmake/px4_impl_os.cmake b/platforms/qurt/cmake/px4_impl_os.cmake index 18ecb396f9..5f0640059b 100644 --- a/platforms/qurt/cmake/px4_impl_os.cmake +++ b/platforms/qurt/cmake/px4_impl_os.cmake @@ -45,6 +45,7 @@ # Required OS Inteface Functions # # * px4_os_add_flags +# * px4_os_determine_build_chip # * px4_os_prebuild_targets # @@ -144,6 +145,23 @@ function(px4_os_add_flags) endfunction() +#============================================================================= +# +# px4_os_determine_build_chip +# +# Sets PX4_CHIP and PX4_CHIP_MANUFACTURER. +# +# Usage: +# px4_os_determine_build_chip() +# +function(px4_os_determine_build_chip) + + # always use generic chip and chip manufacturer + set(PX4_CHIP "generic" CACHE STRING "PX4 Chip" FORCE) + set(PX4_CHIP_MANUFACTURER "generic" CACHE STRING "PX4 Chip Manufacturer" FORCE) + +endfunction() + #============================================================================= # # px4_os_prebuild_targets diff --git a/platforms/qurt/src/px4/CMakeLists.txt b/platforms/qurt/src/px4/CMakeLists.txt new file mode 100644 index 0000000000..929788b587 --- /dev/null +++ b/platforms/qurt/src/px4/CMakeLists.txt @@ -0,0 +1,37 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(common) + +add_subdirectory(${PX4_CHIP_MANUFACTURER}) + diff --git a/platforms/qurt/src/px4_layer/CMakeLists.txt b/platforms/qurt/src/px4/common/CMakeLists.txt similarity index 96% rename from platforms/qurt/src/px4_layer/CMakeLists.txt rename to platforms/qurt/src/px4/common/CMakeLists.txt index 892a6e6684..1e168c4110 100644 --- a/platforms/qurt/src/px4_layer/CMakeLists.txt +++ b/platforms/qurt/src/px4/common/CMakeLists.txt @@ -40,7 +40,7 @@ set(QURT_LAYER_SRCS px4_qurt_impl.cpp px4_qurt_tasks.cpp lib_crc32.c - ../../../posix/src/px4_layer/drv_hrt.cpp + ${PX4_SOURCE_DIR}/platforms/posix/src/px4/common/drv_hrt.cpp qurt_stubs.c main.cpp shmem_qurt.cpp @@ -49,8 +49,8 @@ set(QURT_LAYER_SRCS if ("${QURT_ENABLE_STUBS}" STREQUAL "1") list(APPEND QURT_LAYER_SRCS - ../stubs/stubs_posix.c - ../stubs/stubs_qurt.c + stubs/posix.c + stubs/qurt.c ) endif() diff --git a/platforms/qurt/src/px4_layer/commands_hil.c b/platforms/qurt/src/px4/common/commands_hil.c similarity index 100% rename from platforms/qurt/src/px4_layer/commands_hil.c rename to platforms/qurt/src/px4/common/commands_hil.c diff --git a/platforms/qurt/src/px4_layer/get_commands.h b/platforms/qurt/src/px4/common/get_commands.h similarity index 100% rename from platforms/qurt/src/px4_layer/get_commands.h rename to platforms/qurt/src/px4/common/get_commands.h diff --git a/platforms/qurt/src/px4/common/include/px4_platform/micro_hal.h b/platforms/qurt/src/px4/common/include/px4_platform/micro_hal.h new file mode 100644 index 0000000000..d09b73c687 --- /dev/null +++ b/platforms/qurt/src/px4/common/include/px4_platform/micro_hal.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + +#include + diff --git a/platforms/qurt/src/px4_layer/lib_crc32.c b/platforms/qurt/src/px4/common/lib_crc32.c similarity index 100% rename from platforms/qurt/src/px4_layer/lib_crc32.c rename to platforms/qurt/src/px4/common/lib_crc32.c diff --git a/platforms/qurt/src/px4_layer/main.cpp b/platforms/qurt/src/px4/common/main.cpp similarity index 100% rename from platforms/qurt/src/px4_layer/main.cpp rename to platforms/qurt/src/px4/common/main.cpp diff --git a/platforms/qurt/src/px4_layer/px4_init.cpp b/platforms/qurt/src/px4/common/px4_init.cpp similarity index 100% rename from platforms/qurt/src/px4_layer/px4_init.cpp rename to platforms/qurt/src/px4/common/px4_init.cpp diff --git a/platforms/qurt/src/px4_layer/px4_qurt_impl.cpp b/platforms/qurt/src/px4/common/px4_qurt_impl.cpp similarity index 100% rename from platforms/qurt/src/px4_layer/px4_qurt_impl.cpp rename to platforms/qurt/src/px4/common/px4_qurt_impl.cpp diff --git a/platforms/qurt/src/px4_layer/px4_qurt_tasks.cpp b/platforms/qurt/src/px4/common/px4_qurt_tasks.cpp similarity index 100% rename from platforms/qurt/src/px4_layer/px4_qurt_tasks.cpp rename to platforms/qurt/src/px4/common/px4_qurt_tasks.cpp diff --git a/platforms/qurt/src/px4_layer/qurt_stubs.c b/platforms/qurt/src/px4/common/qurt_stubs.c similarity index 100% rename from platforms/qurt/src/px4_layer/qurt_stubs.c rename to platforms/qurt/src/px4/common/qurt_stubs.c diff --git a/platforms/qurt/src/px4_layer/shmem_qurt.cpp b/platforms/qurt/src/px4/common/shmem_qurt.cpp similarity index 100% rename from platforms/qurt/src/px4_layer/shmem_qurt.cpp rename to platforms/qurt/src/px4/common/shmem_qurt.cpp diff --git a/platforms/qurt/src/px4/common/stubs/posix.c b/platforms/qurt/src/px4/common/stubs/posix.c new file mode 100644 index 0000000000..24b22f13f9 --- /dev/null +++ b/platforms/qurt/src/px4/common/stubs/posix.c @@ -0,0 +1,159 @@ +#include +#include +#include +#include +#include + +int sem_init(sem_t *sem, int pshared, unsigned int value) +{ + return 1; +} + +int sem_wait(sem_t *sem) +{ + return 1; +} + +int sem_destroy(sem_t *sem) +{ + return 1; +} + +int sem_post(sem_t *sem) +{ + return 1; +} + +int sem_getvalue(sem_t *sem, int *sval) +{ + return 1; +} + +int usleep(useconds_t usec) +{ + return 0; +} + +pthread_t pthread_self(void) +{ + pthread_t x = 0; + return x; +} + + +int pthread_kill(pthread_t thread, int sig) +{ + return 1; +} + +void pthread_exit(void *retval) +{ +} + +int pthread_join(pthread_t thread, void **retval) +{ + return 1; +} + +int pthread_cancel(pthread_t thread) +{ + return 1; +} +int pthread_attr_init(pthread_attr_t *attr) +{ + return 1; +} + +int pthread_attr_setstacksize(pthread_attr_t *attr, size_t stacksize) +{ + return 1; +} + +int pthread_attr_getstacksize(const pthread_attr_t *attr, size_t *stacksize) +{ + return 1; +} + +int pthread_attr_setschedparam(pthread_attr_t *attr, const struct sched_param *param) +{ + return 1; +} + +int pthread_create(pthread_t *thread, const pthread_attr_t *attr, void *(*start_routine)(void *), void *arg) +{ + return 1; +} +int pthread_attr_getschedparam(const pthread_attr_t *attr, struct sched_param *param) +{ + return 1; +} + +int pthread_attr_destroy(pthread_attr_t *attr) +{ + return 1; +} + +int clock_gettime(clockid_t clk_id, struct timespec *tp) +{ + return 1; +} + +int pthread_mutex_lock(pthread_mutex_t *mutex) +{ + return 1; +} + +int pthread_mutex_unlock(pthread_mutex_t *mutex) +{ + return 1; +} + +int pthread_cond_signal(pthread_cond_t *cond) +{ + return 1; +} +int pthread_mutex_destroy(pthread_mutex_t *mutex) +{ + return 1; +} +int pthread_mutex_init(pthread_mutex_t *mutex, const pthread_mutexattr_t *attr) +{ + return 1; +} + +int pthread_cond_wait(pthread_cond_t *cond, pthread_mutex_t *mutex) +{ + return 1; +} + +int pthread_cond_timedwait(pthread_cond_t *cond, pthread_mutex_t *mutex, const struct timespec *abstime) +{ + return 1; +} + +int pthread_cond_init(pthread_cond_t *cond, const pthread_condattr_t *attr) +{ + return 1; +} +int pthread_mutexattr_init(pthread_mutexattr_t *attr) +{ + return -1; +} +int pthread_mutexattr_destroy(pthread_mutexattr_t *attr) +{ + return -1; +} +int pthread_mutexattr_settype(pthread_mutexattr_t *attr, int type) +{ + return -1; +} + +int pthread_condattr_init(pthread_condattr_t *attr) +{ + return -1; +} + +int fsync(int fd) +{ + return -1; +} diff --git a/platforms/qurt/src/px4/common/stubs/qurt.c b/platforms/qurt/src/px4/common/stubs/qurt.c new file mode 100644 index 0000000000..09a28f52b4 --- /dev/null +++ b/platforms/qurt/src/px4/common/stubs/qurt.c @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (C) 2015 Mark Charlebois. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#include +#include +#include + +// This code is never run. It is used solely to test linking in the +// TravisCI build test to make sure all symbols are resolved. +__EXPORT int _start_main(void); + +void HAP_debug(const char *msg, int level, const char *filename, int line) +{ +} + +void HAP_power_request(int a, int b, int c) +{ +} + +int dlinit(int a, char **b) +{ + return 1; +} + +int main(int argc, char *argv[]) +{ + int ret = 0; + + return ret; +} + +int _start_main() +{ + return -1; +} diff --git a/platforms/qurt/src/px4/generic/CMakeLists.txt b/platforms/qurt/src/px4/generic/CMakeLists.txt new file mode 100644 index 0000000000..ec489bf559 --- /dev/null +++ b/platforms/qurt/src/px4/generic/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +add_subdirectory(${PX4_CHIP}) + diff --git a/platforms/qurt/src/CMakeLists.txt b/platforms/qurt/src/px4/generic/generic/CMakeLists.txt similarity index 94% rename from platforms/qurt/src/CMakeLists.txt rename to platforms/qurt/src/px4/generic/generic/CMakeLists.txt index 602b1b7107..c4e98943e4 100644 --- a/platforms/qurt/src/CMakeLists.txt +++ b/platforms/qurt/src/px4/generic/generic/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2019 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -31,4 +31,5 @@ # ############################################################################ -add_subdirectory(px4_layer) + + diff --git a/platforms/qurt/src/px4/generic/generic/include/px4_arch/micro_hal.h b/platforms/qurt/src/px4/generic/generic/include/px4_arch/micro_hal.h new file mode 100644 index 0000000000..d09b73c687 --- /dev/null +++ b/platforms/qurt/src/px4/generic/generic/include/px4_arch/micro_hal.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + +#include + diff --git a/src/drivers/px4io/CMakeLists.txt b/src/drivers/px4io/CMakeLists.txt index b5b9881cb8..e7fb8eb177 100644 --- a/src/drivers/px4io/CMakeLists.txt +++ b/src/drivers/px4io/CMakeLists.txt @@ -38,11 +38,10 @@ px4_add_module( -Wno-cast-align # TODO: fix and enable SRCS px4io.cpp - px4io_uploader.cpp px4io_serial.cpp - px4io_serial_f4.cpp - px4io_serial_f7.cpp + px4io_uploader.cpp DEPENDS + arch_px4io_serial circuit_breaker mixer ) diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp index e3808c80e8..0dea74ba6d 100644 --- a/src/drivers/px4io/px4io_serial.cpp +++ b/src/drivers/px4io/px4io_serial.cpp @@ -39,14 +39,14 @@ #include "px4io_driver.h" -#include "px4io_serial.h" +#include static PX4IO_serial *g_interface; device::Device *PX4IO_serial_interface() { - return new PX4IO_INTERFACE_CLASS(); + return new ArchPX4IOSerial(); } PX4IO_serial::PX4IO_serial() : diff --git a/src/drivers/tone_alarm/CMakeLists.txt b/src/drivers/tone_alarm/CMakeLists.txt index f51963a178..a298671f8b 100644 --- a/src/drivers/tone_alarm/CMakeLists.txt +++ b/src/drivers/tone_alarm/CMakeLists.txt @@ -38,6 +38,6 @@ px4_add_module( ToneAlarm.cpp DEPENDS circuit_breaker - tone_alarm_interface + arch_tone_alarm tunes ) diff --git a/src/modules/px4iofirmware/CMakeLists.txt b/src/modules/px4iofirmware/CMakeLists.txt index b3a37b6220..6dcb90f817 100644 --- a/src/modules/px4iofirmware/CMakeLists.txt +++ b/src/modules/px4iofirmware/CMakeLists.txt @@ -45,6 +45,7 @@ add_library(px4iofirmware set_property(GLOBAL APPEND PROPERTY PX4_MODULE_LIBRARIES px4iofirmware) target_link_libraries(px4iofirmware PUBLIC + arch_io_pins nuttx_apps nuttx_arch nuttx_c @@ -52,4 +53,4 @@ target_link_libraries(px4iofirmware rc perf pwm_limit -) \ No newline at end of file +) diff --git a/src/platforms/px4_micro_hal.h b/src/platforms/px4_micro_hal.h index 62b8b9261e..2423902b40 100644 --- a/src/platforms/px4_micro_hal.h +++ b/src/platforms/px4_micro_hal.h @@ -31,199 +31,11 @@ * ****************************************************************************/ #pragma once + /* * This file is a shim to bridge to the many SoC architecture supported by PX4 */ -#ifdef __PX4_NUTTX -__BEGIN_DECLS -#include -#include +// include arch-specific header +#include -/* For historical reasons (NuttX STM32 numbering) PX4 bus numbering is 1 based - * All PX4 code, including, board code is written to assuming 1 based numbering. - * The following macros are used to allow the board config to define the bus - * numbers in terms of the NuttX driver numbering. 1,2,3 for one based numbering - * schemes or 0,1,2 for zero based schemes. - */ - -#define PX4_BUS_NUMBER_TO_PX4(x) ((x)+PX4_BUS_OFFSET) /* Use to define Zero based to match Nuttx Driver but provide 1 based to PX4 */ -#define PX4_BUS_NUMBER_FROM_PX4(x) ((x)-PX4_BUS_OFFSET) /* Use to map PX4 1 based to NuttX driver 0 based */ - -# define px4_enter_critical_section() enter_critical_section() -# define px4_leave_critical_section(flags) leave_critical_section(flags) - -# if defined(CONFIG_ARCH_CHIP_STM32) || defined(CONFIG_ARCH_CHIP_STM32F7) - -# if defined(CONFIG_ARCH_CHIP_STM32) -# include -# define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F4 -# define PX4_FLASH_BASE STM32_FLASH_BASE -# if defined(CONFIG_STM32_STM32F4XXX) -# include -# define PX4_BBSRAM_SIZE STM32_BBSRAM_SIZE -# define PX4_BBSRAM_GETDESC_IOCTL STM32_BBSRAM_GETDESC_IOCTL -# endif -# define PX4_NUMBER_I2C_BUSES STM32_NI2C -# endif - -# if defined(CONFIG_ARCH_CHIP_STM32F7) -# define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32F7 -# include -# include -void stm32_flash_lock(void); -void stm32_flash_unlock(void); -int stm32_flash_writeprotect(size_t page, bool enabled); -# include //include up_systemreset() which is included on stm32.h -# include -# define PX4_BBSRAM_SIZE STM32F7_BBSRAM_SIZE -# define PX4_BBSRAM_GETDESC_IOCTL STM32F7_BBSRAM_GETDESC_IOCTL -# define PX4_FLASH_BASE 0x08000000 -# define PX4_NUMBER_I2C_BUSES STM32F7_NI2C -# endif - -# include -# include -# include - -/* STM32/32F7 defines the 96 bit UUID as - * init32_t[3] that can be read as bytes/half-words/words - * init32_t[0] PX4_CPU_UUID_ADDRESS[0] bits 31:0 (offset 0) - * init32_t[1] PX4_CPU_UUID_ADDRESS[1] bits 63:32 (offset 4) - * init32_t[2] PX4_CPU_UUID_ADDRESS[3] bits 96:64 (offset 8) - * - * The original PX4 stm32 (legacy) based implementation **displayed** the - * UUID as: ABCD EFGH IJKL - * Where: - * A was bit 31 and D was bit 0 - * E was bit 63 and H was bit 32 - * I was bit 95 and L was bit 64 - * - * Since the string was used by some manufactures to identify the units - * it must be preserved. - * - * For new targets moving forward we will use - * IJKL EFGH ABCD - */ -# define PX4_CPU_UUID_BYTE_LENGTH 12 -# define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t)) - -/* The mfguid will be an array of bytes with - * MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1 - * - * It will be converted to a string with the MSD on left and LSD on the right most position. - */ -# define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH - -/* By not defining PX4_CPU_UUID_CORRECT_CORRELATION the following maintains the legacy incorrect order - * used for selection of significant digits of the UUID in the PX4 code base. - * This is done to avoid the ripple effects changing the IDs used on STM32 base platforms - */ -# if defined(PX4_CPU_UUID_CORRECT_CORRELATION) -# define PX4_CPU_UUID_WORD32_UNIQUE_H 0 /* Least significant digits change the most */ -# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */ -# define PX4_CPU_UUID_WORD32_UNIQUE_L 2 /* Most significant digits change the least */ -# else -/* Legacy incorrect ordering */ -# define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */ -# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */ -# define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */ -# endif - -/* Separator nnn:nnn:nnnn 2 char per byte term */ -# define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1) -# define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1) - -# define px4_savepanic(fileno, context, length) stm32_bbsram_savepanic(fileno, context, length) - -# define PX4_BUS_OFFSET 0 /* STM buses are 1 based no adjustment needed */ -# define px4_spibus_initialize(bus_num_1based) stm32_spibus_initialize(bus_num_1based) - -# define px4_i2cbus_initialize(bus_num_1based) stm32_i2cbus_initialize(bus_num_1based) -# define px4_i2cbus_uninitialize(pdev) stm32_i2cbus_uninitialize(pdev) - -# define px4_arch_configgpio(pinset) stm32_configgpio(pinset) -# define px4_arch_unconfiggpio(pinset) stm32_unconfiggpio(pinset) -# define px4_arch_gpioread(pinset) stm32_gpioread(pinset) -# define px4_arch_gpiowrite(pinset, value) stm32_gpiowrite(pinset, value) -# define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) stm32_gpiosetevent(pinset,r,f,e,fp,a) -#endif // defined(CONFIG_ARCH_CHIP_STM32) || defined(CONFIG_ARCH_CHIP_STM32F7) - -#if defined(CONFIG_ARCH_CHIP_KINETIS) -# define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_KINETISK66 - -# // Fixme: using ?? -# define PX4_BBSRAM_SIZE 2048 -# define PX4_BBSRAM_GETDESC_IOCTL 0 -# define PX4_NUMBER_I2C_BUSES KINETIS_NI2C - -# define GPIO_OUTPUT_SET GPIO_OUTPUT_ONE -# define GPIO_OUTPUT_CLEAR GPIO_OUTPUT_ZERO - -# include -# include -# include -# include - -/* Kinetis defines the 128 bit UUID as - * init32_t[4] that can be read as words - * init32_t[0] PX4_CPU_UUID_ADDRESS[0] bits 127:96 (offset 0) - * init32_t[1] PX4_CPU_UUID_ADDRESS[1] bits 95:64 (offset 4) - * init32_t[2] PX4_CPU_UUID_ADDRESS[1] bits 63:32 (offset 8) - * init32_t[3] PX4_CPU_UUID_ADDRESS[3] bits 31:0 (offset C) - * - * PX4 uses the words in bigendian order MSB to LSB - * word [0] [1] [2] [3] - * bits 127:96 95-64 63-32, 31-00, - */ -# define PX4_CPU_UUID_BYTE_LENGTH KINETIS_UID_SIZE -# define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t)) - -/* The mfguid will be an array of bytes with - * MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1 - * - * It will be converted to a string with the MSD on left and LSD on the right most position. - */ -# define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH - -/* define common formating across all commands */ - -# define PX4_CPU_UUID_WORD32_FORMAT "%08x" -# define PX4_CPU_UUID_WORD32_SEPARATOR ":" - -# define PX4_CPU_UUID_WORD32_UNIQUE_H 3 /* Least significant digits change the most */ -# define PX4_CPU_UUID_WORD32_UNIQUE_M 2 /* Middle High significant digits */ -# define PX4_CPU_UUID_WORD32_UNIQUE_L 1 /* Middle Low significant digits */ -# define PX4_CPU_UUID_WORD32_UNIQUE_N 0 /* Most significant digits change the least */ - -/* Separator nnn:nnn:nnnn 2 char per byte term */ -# define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1) -# define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1) - -# define kinetis_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet - -# define px4_savepanic(fileno, context, length) kinetis_bbsram_savepanic(fileno, context, length) - -/* bus_num is zero based on kinetis and must be translated from the legacy one based */ - -# define PX4_BUS_OFFSET 1 /* Kinetis buses are 0 based and adjustment is needed */ - -# define px4_spibus_initialize(bus_num_1based) kinetis_spibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based)) - -# define px4_i2cbus_initialize(bus_num_1based) kinetis_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based)) -# define px4_i2cbus_uninitialize(pdev) kinetis_i2cbus_uninitialize(pdev) - -# define px4_arch_configgpio(pinset) kinetis_pinconfig(pinset) -# define px4_arch_unconfiggpio(pinset) -# define px4_arch_gpioread(pinset) kinetis_gpioread(pinset) -# define px4_arch_gpiowrite(pinset, value) kinetis_gpiowrite(pinset, value) - -/* kinetis_gpiosetevent is not implemented and will need to be added */ - -# define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) kinetis_gpiosetevent(pinset,r,f,e,fp,a) -# endif - -#include - -__END_DECLS -#endif