mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-02 08:50:05 +08:00
Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 263d2d6e2b |
@@ -66,11 +66,8 @@ pipeline {
|
||||
"mro_ctrl-zero-f7_default",
|
||||
"mro_ctrl-zero-f7-oem_default",
|
||||
"mro_ctrl-zero-h7_default",
|
||||
"mro_ctrl-zero-h7_rtps",
|
||||
"mro_ctrl-zero-h7-oem_default",
|
||||
"mro_ctrl-zero-h7-oem_rtps",
|
||||
"mro_pixracerpro_default",
|
||||
"mro_pixracerpro_rtps",
|
||||
"mro_x21-777_default",
|
||||
"mro_x21_default",
|
||||
"nxp_fmuk66-e_default",
|
||||
@@ -97,6 +94,7 @@ pipeline {
|
||||
"px4_fmu-v5_stackcheck",
|
||||
"px4_fmu-v5_uavcanv0periph",
|
||||
"px4_fmu-v5_uavcanv1",
|
||||
"px4_fmu-v5x_base_phy_DP83848C",
|
||||
"px4_fmu-v5x_default",
|
||||
"px4_fmu-v6u_default",
|
||||
"px4_fmu-v6x_default",
|
||||
|
||||
+29
-51
@@ -21,7 +21,7 @@ pipeline {
|
||||
sh 'make cubepilot_cubeorange_bootloader'
|
||||
sh 'make cubepilot_cubeorange_test'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*, build/cubepilot_cubeorange_test/etc/init.d/airframes/*', name: 'cubepilot_cubeorange_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*, build/cubepilot_cubeorange_test/etc/init.d/airframes/*', name: 'cubepilot_cubeorange_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -42,7 +42,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/cubepilot_cubeorange_bootloader/cubepilot_cubeorange_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/cubepilot_cubeorange_test/cubepilot_cubeorange_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -74,7 +73,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/cubepilot_cubeorange_test/cubepilot_cubeorange_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/cubepilot_cubeorange_test/cubepilot_cubeorange_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -95,7 +95,7 @@ pipeline {
|
||||
sh 'make cuav_x7pro_bootloader'
|
||||
sh 'make cuav_x7pro_test'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'cuav_x7pro_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'cuav_x7pro_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -116,7 +116,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/cuav_x7pro_bootloader/cuav_x7pro_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/cuav_x7pro_test/cuav_x7pro_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -143,7 +142,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/cuav_x7pro_test/cuav_x7pro_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/cuav_x7pro_test/cuav_x7pro_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -164,7 +164,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v3_test'
|
||||
sh 'make px4_fmu-v3_test bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v3_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v3_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -185,7 +185,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v3_test/px4_fmu-v3_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v3_test/px4_fmu-v3_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -212,7 +211,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v3_test/px4_fmu-v3_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v3_test/px4_fmu-v3_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -233,7 +233,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v4_test'
|
||||
sh 'make px4_fmu-v4_test bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v4_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v4_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -254,7 +254,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4_test/px4_fmu-v4_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4_test/px4_fmu-v4_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -280,7 +279,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v4_test/px4_fmu-v4_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v4_test/px4_fmu-v4_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -301,7 +301,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v4pro_test'
|
||||
sh 'make px4_fmu-v4pro_test bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v4pro_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v4pro_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -322,7 +322,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4pro_test/px4_fmu-v4pro_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4pro_test/px4_fmu-v4pro_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -349,7 +348,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v4pro_test/px4_fmu-v4pro_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v4pro_test/px4_fmu-v4pro_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -370,7 +370,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v5_debug'
|
||||
sh 'make px4_fmu-v5_debug bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v5_debug'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v5_debug'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -396,7 +396,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_debug/px4_fmu-v5_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_debug/px4_fmu-v5_debug.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600 || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -409,10 +408,7 @@ pipeline {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -v"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -u -v"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_stress"'
|
||||
|
||||
// test dataman
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests dataman"'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests file" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests latency_test" || true'
|
||||
@@ -439,7 +435,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v5_debug/px4_fmu-v5_debug.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v5_debug/px4_fmu-v5_debug.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -460,7 +457,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v5_stackcheck'
|
||||
sh 'make px4_fmu-v5_stackcheck bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v5_stackcheck'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v5_stackcheck'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -486,7 +483,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -495,9 +491,6 @@ pipeline {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests latency_test" || true'
|
||||
|
||||
// test dataman
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests dataman"'
|
||||
}
|
||||
}
|
||||
stage("status") {
|
||||
@@ -521,7 +514,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -542,7 +536,7 @@ pipeline {
|
||||
sh 'make px4_fmu-v5_test'
|
||||
sh 'make px4_fmu-v5_test bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'px4_fmu-v5_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'px4_fmu-v5_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -563,7 +557,6 @@ pipeline {
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_test/px4_fmu-v5_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_test/px4_fmu-v5_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -590,7 +583,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/px4_fmu-v5_test/px4_fmu-v5_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/px4_fmu-v5_test/px4_fmu-v5_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -611,7 +605,7 @@ pipeline {
|
||||
sh 'make nxp_fmuk66-v3_test'
|
||||
//sh 'make nxp_fmuk66-v3_test bootloader_elf'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, platforms/nuttx/NuttX/nuttx/tools/nuttx-gdbinit, Tools/HIL/*', name: 'nxp_fmuk66-v3_test'
|
||||
stash includes: 'build/*/*.elf, platforms/nuttx/Debug/*, Tools/HIL/*', name: 'nxp_fmuk66-v3_test'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
@@ -632,7 +626,6 @@ pipeline {
|
||||
//sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/nxp_fmuk66-v3_test/nxp_fmuk66-v3_bootloader.elf'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/nxp_fmuk66-v3_test/nxp_fmuk66-v3_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-*` --baudrate 57600'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
@@ -659,7 +652,8 @@ pipeline {
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace_simple.sh build/nxp_fmuk66-v3_test/nxp_fmuk66-v3_test.elf || true'
|
||||
sh './platforms/nuttx/Debug/jlink_gdb_backtrace.sh build/nxp_fmuk66-v3_test/nxp_fmuk66-v3_test.elf || true'
|
||||
resetBoard()
|
||||
}
|
||||
}
|
||||
} // stage test
|
||||
@@ -794,15 +788,13 @@ void runTests() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests latency_test" || true'
|
||||
|
||||
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *usb-*`'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests file" || true'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd readtest"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd rwtest"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd erase"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -v"'
|
||||
@@ -810,22 +802,13 @@ void runTests() {
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_stress"'
|
||||
|
||||
// tests (stop modules first)
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink stop-all"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "navigator stop"'
|
||||
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *usb-*`'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors stop"' // ignore irrelevant sensor timeouts during microbenchmarks
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "microbench all"'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "calib_udelay"'
|
||||
|
||||
// test rebooting multiple times
|
||||
resetParameters()
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set SYS_AUTOSTART 4001" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param save"'
|
||||
sh './Tools/HIL/reboot.py --device `find /dev/serial -name *usb-*`'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
|
||||
@@ -835,8 +818,6 @@ void runTests() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
|
||||
sh './Tools/HIL/reboot.py --device `find /dev/serial -name *usb-*`'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CBRK*; param show SYS*"' // check that CBRK_BUZZER and SYS_AUTOSTART haven't been lost
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/microsd/parameters_backup.bson" || true'
|
||||
}
|
||||
|
||||
void printTopics() {
|
||||
@@ -947,7 +928,6 @@ void resetBoard() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set MAV_0_CONFIG 0" || true' // limit cpu usage
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set MAV_1_CONFIG 0" || true' // limit cpu usage
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set SDLOG_MODE -1" || true' // limit cpu usage
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "echo > /fs/microsd/.format" || true'
|
||||
sh './Tools/HIL/reboot.py --device `find /dev/serial -name *usb-*`' // reboot to apply
|
||||
|
||||
// check SD card
|
||||
@@ -972,6 +952,4 @@ void resetBoard() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage" || true'
|
||||
|
||||
sh './Tools/HIL/reboot.py --device `find /dev/serial -name *usb-*`' // reboot to apply
|
||||
}
|
||||
|
||||
@@ -15,10 +15,10 @@ jobs:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
config:
|
||||
- {model: "iris", latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo" } # Alaska
|
||||
- {model: "standard_vtol", latitude: "-38.071235", longitude: "145.281220", altitude: "31", build_type: "AddressSanitizer" } # Australia
|
||||
- {model: "tailsitter" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida
|
||||
- {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich
|
||||
- {latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo", model: "iris" } # Alaska
|
||||
- {latitude: "-38.071235", longitude: "145.281220", altitude: "31", build_type: "AddressSanitizer", model: "standard_vtol" } # Australia
|
||||
- {latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo", model: "tailsitter" } # Florida
|
||||
- {latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage", model: "standard_vtol" } # Zurich
|
||||
|
||||
container:
|
||||
image: px4io/px4-dev-simulation-focal:2021-09-08
|
||||
@@ -96,7 +96,7 @@ jobs:
|
||||
PX4_HOME_LON: ${{matrix.config.longitude}}
|
||||
PX4_HOME_ALT: ${{matrix.config.altitude}}
|
||||
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
|
||||
run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json --verbose
|
||||
run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json
|
||||
timeout-minutes: 45
|
||||
|
||||
- name: Look at core files
|
||||
|
||||
@@ -105,4 +105,8 @@ src/lib/version/build_git_version.h
|
||||
src/modules/simulator/simulator_config.h
|
||||
src/systemcmds/topic_listener/listener_generated.cpp
|
||||
|
||||
# SITL
|
||||
dataman
|
||||
eeprom/
|
||||
|
||||
!src/drivers/distance_sensor/broadcom/afbrs50/Lib/*
|
||||
|
||||
@@ -42,6 +42,12 @@
|
||||
[submodule "src/drivers/uavcan_v1/public_regulated_data_types"]
|
||||
path = src/drivers/uavcan_v1/public_regulated_data_types
|
||||
url = https://github.com/UAVCAN/public_regulated_data_types.git
|
||||
[submodule "src/drivers/uavcannode_gps_demo/public_regulated_data_types"]
|
||||
path = src/drivers/uavcannode_gps_demo/public_regulated_data_types
|
||||
url = https://github.com/UAVCAN/public_regulated_data_types.git
|
||||
[submodule "src/drivers/uavcannode_gps_demo/libcanard"]
|
||||
path = src/drivers/uavcannode_gps_demo/libcanard
|
||||
url = https://github.com/UAVCAN/libcanard.git
|
||||
[submodule "src/drivers/uavcan_v1/legacy_data_types"]
|
||||
path = src/drivers/uavcan_v1/legacy_data_types
|
||||
url = https://github.com/PX4/public_regulated_data_types.git
|
||||
|
||||
@@ -114,9 +114,14 @@ config BOARD_ETHERNET
|
||||
flag to indicate that ethernet is enabled
|
||||
|
||||
config BOARD_CRYPTO
|
||||
bool "Crypto support"
|
||||
string "Crypto"
|
||||
help
|
||||
Enable PX4 Crypto Support. Select the implementation under drivers
|
||||
Crypto implementation selection
|
||||
|
||||
config BOARD_KEYSTORE
|
||||
string "Keystore"
|
||||
help
|
||||
Keystore implememntation selection
|
||||
|
||||
menu "Serial ports"
|
||||
|
||||
|
||||
@@ -1,7 +1,5 @@
|
||||
#!/bin/sh
|
||||
|
||||
set -e
|
||||
|
||||
# PX4 commands need the 'px4-' prefix in bash.
|
||||
# (px4-alias.sh is expected to be in the PATH)
|
||||
# shellcheck disable=SC1091
|
||||
|
||||
@@ -18,17 +18,8 @@ set OUTPUT_AUX_DEV /dev/pwm_output1
|
||||
set OUTPUT_EXTRA_DEV /dev/pwm_output0
|
||||
|
||||
# set these before starting the modules
|
||||
if [ $PWM_AUX_OUT != none ]
|
||||
then
|
||||
|
||||
param set PWM_AUX_OUT ${PWM_AUX_OUT}
|
||||
fi
|
||||
|
||||
|
||||
if [ $PWM_OUT != none ]
|
||||
then
|
||||
param set PWM_MAIN_OUT ${PWM_OUT}
|
||||
fi
|
||||
param set PWM_AUX_OUT ${PWM_AUX_OUT}
|
||||
param set PWM_MAIN_OUT ${PWM_OUT}
|
||||
|
||||
#
|
||||
# If mount (gimbal) control is enabled and output mode is AUX, set the aux
|
||||
|
||||
@@ -35,7 +35,7 @@ set MIXER_AUX none
|
||||
set MIXER_FILE none
|
||||
set MIXER_EXTRA none
|
||||
set OUTPUT_MODE none
|
||||
set PARAM_FILE ""
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
set PWM_OUT none
|
||||
set PWM_MAIN_RATE p:PWM_MAIN_RATE
|
||||
set PWM_AUX_OUT none
|
||||
@@ -129,8 +129,6 @@ then
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
fi
|
||||
|
||||
#
|
||||
@@ -163,31 +161,8 @@ else
|
||||
param select $PARAM_FILE
|
||||
if ! param import
|
||||
then
|
||||
echo "ERROR [init] param import failed"
|
||||
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
||||
|
||||
param dump $PARAM_FILE
|
||||
|
||||
if [ -d "/fs/microsd" ]
|
||||
then
|
||||
dmesg >> /fs/microsd/param_import_fail.txt &
|
||||
|
||||
# try to make a backup copy
|
||||
cp $PARAM_FILE /fs/microsd/param_import_fail.bson &
|
||||
fi
|
||||
|
||||
# try importing from backup file
|
||||
if [ -f "/fs/microsd/parameters_backup.bson" ]
|
||||
then
|
||||
param import /fs/microsd/parameters_backup.bson
|
||||
fi
|
||||
param reset_all
|
||||
fi
|
||||
|
||||
if [ $SDCARD_AVAILABLE = yes ]
|
||||
then
|
||||
param select-backup /fs/microsd/parameters_backup.bson
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X
|
||||
then
|
||||
netman update -i eth0
|
||||
@@ -235,16 +210,7 @@ else
|
||||
# Waypoint storage.
|
||||
# REBOOTWORK this needs to start in parallel.
|
||||
#
|
||||
if param compare SYS_DM_BACKEND 1
|
||||
then
|
||||
dataman start -r
|
||||
else
|
||||
if param compare SYS_DM_BACKEND 0
|
||||
then
|
||||
# dataman start default
|
||||
dataman start
|
||||
fi
|
||||
fi
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the socket communication send_event handler.
|
||||
@@ -477,12 +443,6 @@ else
|
||||
rc_input start $RC_INPUT_ARGS
|
||||
fi
|
||||
|
||||
# PPS capture driver (before pwm_out)
|
||||
if param greater -s PPS_CAP_ENABLE 0
|
||||
then
|
||||
pps_capture start
|
||||
fi
|
||||
|
||||
# Camera capture driver (before pwm_out)
|
||||
if param greater -s CAM_CAP_FBACK 0
|
||||
then
|
||||
|
||||
@@ -40,8 +40,8 @@ def monitor_firmware_upload(port, baudrate):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout = 180 # 3 minutes
|
||||
timeout_start = time.monotonic()
|
||||
timeout_newline = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout_newline = time.time()
|
||||
|
||||
return_code = 0
|
||||
|
||||
@@ -59,13 +59,13 @@ def monitor_firmware_upload(port, baudrate):
|
||||
elif "nsh>" in serial_line:
|
||||
sys.exit(return_code)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
# newline every 10 seconds if still running
|
||||
if time.monotonic() - timeout_newline > 10:
|
||||
timeout_newline = time.monotonic()
|
||||
if time.time() - timeout_newline > 10:
|
||||
timeout_newline = time.time()
|
||||
ser.write("\n".encode("ascii"))
|
||||
ser.flush()
|
||||
|
||||
|
||||
+11
-13
@@ -34,7 +34,7 @@ def print_line(line):
|
||||
def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.1, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@@ -50,7 +50,7 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
sys.exit(1)
|
||||
|
||||
@@ -58,13 +58,12 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
ser.readlines()
|
||||
|
||||
# run command
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 10 # 10 seconds
|
||||
|
||||
cmd = "param set " + param_name + " " + param_value
|
||||
|
||||
# write command (param set) and wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}\r\n'.format(cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@@ -78,7 +77,7 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
@@ -90,8 +89,8 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
|
||||
param_show_response = param_name + " ["
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 3 # 3 seconds
|
||||
timeout_start = time.time()
|
||||
timeout = 2 # 2 seconds
|
||||
|
||||
while True:
|
||||
serial_line = ser.readline().decode("ascii", errors='ignore')
|
||||
@@ -108,20 +107,19 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
if "nsh>" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
elif "NuttShell (NSH)" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
if len(serial_line) <= 0:
|
||||
ser.write("\r\n".encode("ascii"))
|
||||
ser.flush()
|
||||
time.sleep(0.2)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
+12
-11
@@ -36,29 +36,26 @@ def print_line(line):
|
||||
else:
|
||||
print('{0}'.format(line), end='')
|
||||
|
||||
def reboot(port, baudrate):
|
||||
def monitor_firmware_upload(port, baudrate):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
# clear
|
||||
ser.readlines()
|
||||
|
||||
time_start = time.monotonic()
|
||||
ser.write("\nreboot\n".encode("ascii"))
|
||||
ser.flush()
|
||||
time_reboot_cmd = time_start
|
||||
|
||||
timeout_reboot_cmd = 90
|
||||
timeout_reboot_cmd = 30
|
||||
timeout = 300 # 5 minutes
|
||||
timeout_start = time.time()
|
||||
timeout_newline = time.time()
|
||||
time_success = 0
|
||||
|
||||
return_code = 0
|
||||
|
||||
while True:
|
||||
if time.monotonic() > time_reboot_cmd + timeout_reboot_cmd:
|
||||
time_reboot_cmd = time.monotonic()
|
||||
print("sending reboot cmd again")
|
||||
if time.time() > timeout_start + timeout_reboot_cmd:
|
||||
ser.write("reboot\n".encode("ascii"))
|
||||
ser.flush()
|
||||
time.sleep(0.2)
|
||||
|
||||
serial_line = ser.readline().decode("ascii", errors='ignore')
|
||||
|
||||
@@ -69,9 +66,13 @@ def reboot(port, baudrate):
|
||||
print_line(serial_line)
|
||||
|
||||
if "NuttShell (NSH)" in serial_line:
|
||||
time_success = time.time()
|
||||
|
||||
# wait at least 2 seconds after seeing prompt to catch potential errors
|
||||
if time_success > 0 and time.time() > time_success + 2:
|
||||
sys.exit(return_code)
|
||||
|
||||
if time.monotonic() > time_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
@@ -81,7 +82,7 @@ def main():
|
||||
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
|
||||
args = parser.parse_args()
|
||||
|
||||
reboot(args.device, args.baudrate)
|
||||
monitor_firmware_upload(args.device, args.baudrate)
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
|
||||
+10
-12
@@ -40,7 +40,7 @@ def print_line(line):
|
||||
def do_nsh_cmd(port, baudrate, cmd):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.2, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@@ -56,7 +56,7 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
sys.exit(1)
|
||||
|
||||
@@ -64,13 +64,12 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
ser.readlines()
|
||||
|
||||
# run command
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 1 # 1 second
|
||||
|
||||
success_cmd = "cmd succeeded!"
|
||||
|
||||
# wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}; echo "{1}"; echo "{2}";\r\n'.format(cmd, success_cmd, success_cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@@ -87,13 +86,13 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if (len(serial_line) <= 0) and (time.monotonic() > timeout_start + timeout):
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 240 # 4 minutes
|
||||
timeout_start = time.time()
|
||||
timeout = 180 # 3 minutes
|
||||
|
||||
return_code = 0
|
||||
|
||||
@@ -115,14 +114,13 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
elif "NuttShell (NSH)" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
|
||||
if (len(serial_line) <= 0) and (time.monotonic() > timeout_start + timeout):
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
if len(serial_line) <= 0:
|
||||
ser.write("\r\n".encode("ascii"))
|
||||
ser.flush()
|
||||
time.sleep(0.2)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
@@ -41,7 +41,7 @@ def print_line(line):
|
||||
def do_test(port, baudrate, test_name):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.2, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@@ -57,7 +57,7 @@ def do_test(port, baudrate, test_name):
|
||||
if len(serial_line) > 0:
|
||||
print(serial_line, end='')
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
return False
|
||||
|
||||
@@ -72,11 +72,10 @@ def do_test(port, baudrate, test_name):
|
||||
print("| Running:", cmd)
|
||||
print('|======================================================================')
|
||||
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout = 2 # 2 seconds
|
||||
|
||||
# wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}\n'.format(cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@@ -89,14 +88,14 @@ def do_test(port, baudrate, test_name):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
|
||||
# print results, wait for final result (PASSED or FAILED)
|
||||
timeout = 300 # 5 minutes
|
||||
timeout_start = time.monotonic()
|
||||
timeout_start = time.time()
|
||||
timeout_newline = timeout_start
|
||||
|
||||
while True:
|
||||
@@ -112,16 +111,16 @@ def do_test(port, baudrate, test_name):
|
||||
success = False
|
||||
break
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
print(test_name + f" {COLOR_RED}FAILED{COLOR_RESET}")
|
||||
success = False
|
||||
break
|
||||
|
||||
# newline every 10 seconds if still running
|
||||
if (len(serial_line) <= 0) and (time.monotonic() - timeout_newline > 10):
|
||||
if time.time() - timeout_newline > 10:
|
||||
ser.write("\n".encode("ascii"))
|
||||
timeout_newline = time.monotonic()
|
||||
timeout_newline = time.time()
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
@@ -41,9 +41,7 @@ def process_target(px4board_file, target_name):
|
||||
platform = None
|
||||
toolchain = None
|
||||
|
||||
if px4board_file.endswith("default.px4board") or \
|
||||
px4board_file.endswith("recovery.px4board") or \
|
||||
px4board_file.endswith("bootloader.px4board"):
|
||||
if px4board_file.endswith("default.px4board"):
|
||||
kconf.load_config(px4board_file, replace=True)
|
||||
else: # Merge config with default.px4board
|
||||
default_kconfig = re.sub(r'[a-zA-Z\d_]+\.px4board', 'default.px4board', px4board_file)
|
||||
|
||||
@@ -92,7 +92,6 @@ pca9685,CONFIG_DRIVERS_PCA9685=y
|
||||
pca9685_pwm_out,CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
power_monitor/ina226,CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
power_monitor/voxlpm,CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
|
||||
pps_capture,CONFIG_DRIVERS_PPS_CAPTURE=y
|
||||
protocol_splitter,CONFIG_DRIVERS_PROTOCOL_SPLITTER=y
|
||||
pwm_input,CONFIG_DRIVERS_PWM_INPUT=y
|
||||
pwm_out_sim,CONFIG_DRIVERS_PWM_OUT_SIM=y
|
||||
|
||||
@@ -111,7 +111,7 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
|
||||
for key in param['values']:
|
||||
tags += '\n * @value {:} {:}'.format(key, param['values'][key])
|
||||
elif param['type'] == 'boolean':
|
||||
param_type = 'BOOL'
|
||||
param_type = 'INT32'
|
||||
tags += '\n * @boolean'
|
||||
elif param['type'] == 'int32':
|
||||
param_type = 'INT32'
|
||||
@@ -136,6 +136,9 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
|
||||
else:
|
||||
default_value = param['default']
|
||||
|
||||
if type(default_value) == bool:
|
||||
default_value = int(default_value)
|
||||
|
||||
# output the existing C-style format
|
||||
ret += '''
|
||||
/**
|
||||
|
||||
Submodule Tools/simulation-ignition updated: 483193d9b8...0ea4dbe2c3
+1
-1
Submodule Tools/sitl_gazebo updated: 27298574ce...60d6844e17
@@ -42,7 +42,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0030
|
||||
CONFIG_CDCACM_PRODUCTSTR="MindPX FMU v2.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -114,6 +113,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -239,6 +239,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
if (!spi4) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n");
|
||||
board_autoled_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI4 to 10MHz and de-assert the known chip selects. */
|
||||
@@ -254,6 +255,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
if (!spi1) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
|
||||
board_autoled_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI1 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max)
|
||||
@@ -277,7 +279,9 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
|
||||
|
||||
if (!sdio) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
|
||||
CONFIG_NSH_MMCSDSLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||
@@ -285,6 +289,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
|
||||
|
||||
@@ -91,6 +91,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -146,6 +146,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
@@ -93,6 +93,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -151,6 +151,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
@@ -93,6 +93,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -157,6 +157,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
@@ -39,7 +39,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -47,7 +46,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0061
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 ATL Mantis-EDU"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -89,6 +87,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -121,6 +120,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -240,6 +240,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
@@ -51,7 +51,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -79,7 +78,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -93,8 +91,10 @@ CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
|
||||
@@ -175,6 +175,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "[boot] SDIO init failed\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
@@ -14,7 +14,6 @@ CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_LINUX_PWM_OUT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_PWM_OUT_SIM=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
@@ -24,7 +23,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
@@ -48,6 +46,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
|
||||
@@ -12,7 +12,6 @@ CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
@@ -28,11 +27,15 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
@@ -43,7 +46,10 @@ CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_PWM=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||
|
||||
@@ -42,7 +42,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0016
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 Crazyflie v2.0"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
|
||||
@@ -150,7 +150,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
}
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
stm32_spi_bus_initialize();
|
||||
int ret = stm32_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
@@ -404,9 +404,9 @@ Syslink::handle_message(syslink_message_t *msg)
|
||||
memcpy(&vbat, &msg->data[1], sizeof(float));
|
||||
//memcpy(&iset, &msg->data[5], sizeof(float));
|
||||
|
||||
_battery.setConnected(true);
|
||||
_battery.updateVoltage(vbat);
|
||||
_battery.updateAndPublishBatteryStatus(t);
|
||||
_battery.updateBatteryStatus(t, vbat, -1, true,
|
||||
battery_status_s::BATTERY_SOURCE_POWER_MODULE, 0, 0);
|
||||
|
||||
|
||||
// Update battery charge state
|
||||
if (charging) {
|
||||
|
||||
@@ -139,7 +139,7 @@ private:
|
||||
|
||||
// nrf chip schedules battery updates with SYSLINK_SEND_PERIOD_MS
|
||||
static constexpr uint32_t SYSLINK_BATTERY_STATUS_INTERVAL_US = 10_ms;
|
||||
Battery _battery{1, nullptr, SYSLINK_BATTERY_STATUS_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE};
|
||||
Battery _battery{1, nullptr, SYSLINK_BATTERY_STATUS_INTERVAL_US};
|
||||
|
||||
int32_t _rssi;
|
||||
battery_state _bstate;
|
||||
|
||||
@@ -11,7 +11,6 @@ CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
@@ -28,11 +27,15 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
@@ -44,6 +47,7 @@ CONFIG_SYSTEMCMDS_PWM=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
|
||||
@@ -41,7 +41,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0016
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 Crazyflie v2.0"
|
||||
CONFIG_CDCACM_RXBUFSIZE=300
|
||||
|
||||
@@ -150,7 +150,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
}
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
stm32_spi_bus_initialize();
|
||||
int ret = stm32_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
|
||||
@@ -31,7 +31,6 @@ CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
@@ -94,6 +93,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -145,6 +145,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL CUAV Nora"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -52,6 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LIB_BOARDCTL=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=8
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
@@ -46,7 +46,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV Nora"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -88,6 +87,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -121,6 +121,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -201,10 +201,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL CUAV X7Pro"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -52,6 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LIB_BOARDCTL=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=8
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
@@ -46,13 +46,13 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV X7Pro"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3163
|
||||
CONFIG_CDCACM_VENDORSTR="CUAV"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
@@ -60,7 +60,6 @@ CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXAMPLES_CALIB_UDELAY=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
@@ -83,10 +82,12 @@ CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -120,6 +121,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -201,10 +201,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -25,11 +25,10 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=79954
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1016
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL CubePilot CubeOrange"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -52,6 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LIB_BOARDCTL=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=8
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
@@ -60,6 +60,7 @@
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 0
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
@@ -81,55 +82,56 @@
|
||||
* PLLP2,3 = {2, 3, 4, ..., 128}
|
||||
* CPUCLK <= 480 MHz
|
||||
*/
|
||||
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (24,000,000 / 3) * 100 = 800 MHz
|
||||
* PLL1_VCO = (24,000,000 / 2) * 80 = 960 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
* PLL1Q = PLL1_VCO/8 = 800 MHz / 8 = 100 MHz
|
||||
* PLL1R = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
|
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
|
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
|
||||
*/
|
||||
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN)
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(3)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(100)
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(2)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(80)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(8)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 3) * 100)
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 80)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
|
||||
|
||||
/* PLL2 */
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(30)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(4)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(5)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(1)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(32)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
|
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 30)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 4)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 5)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 1)
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 32)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
|
||||
/* PLL3 */
|
||||
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN)
|
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(6)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(72)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(3)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(6)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(9)
|
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(32)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
|
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 6) * 72)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 3)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 6)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 9)
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 32)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
|
||||
/* SYSCLK = PLL1P = 400MHz
|
||||
* CPUCLK = SYSCLK / 1 = 400 MHz
|
||||
/* SYSCLK = PLL1P = 480MHz
|
||||
* CPUCLK = SYSCLK / 1 = 480 MHz
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
|
||||
@@ -138,7 +140,7 @@
|
||||
/* Configure Clock Assignments */
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 200
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
|
||||
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
|
||||
@@ -184,28 +186,36 @@
|
||||
/* Kernel Clock Configuration
|
||||
* Note: look at Table 54 in ST Manual
|
||||
*/
|
||||
#define STM32_RCC_D1CCIPR_SDMMCSEL RCC_D1CCIPR_SDMMC_PLL1
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */
|
||||
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* SDMMC definitions ********************************************************/
|
||||
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
|
||||
#define STM32_SDMMC_INIT_CLKDIV (125 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 100 / (2*25)
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
|
||||
*/
|
||||
#define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
|
||||
@@ -42,12 +42,11 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=79954
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1016
|
||||
CONFIG_CDCACM_PRODUCTSTR="CubeOrange"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -89,6 +88,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -122,6 +122,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -41,18 +41,18 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=79954
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1016
|
||||
CONFIG_CDCACM_PRODUCTSTR="CubeOrange"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x2DAE
|
||||
CONFIG_CDCACM_VENDORSTR="CubePilot"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
@@ -60,7 +60,6 @@ CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXAMPLES_CALIB_UDELAY=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
@@ -83,10 +82,12 @@ CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -120,6 +121,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -181,10 +181,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
Binary file not shown.
@@ -40,7 +40,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -48,7 +47,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1012
|
||||
CONFIG_CDCACM_PRODUCTSTR="CubeYellow"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -75,7 +73,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -88,8 +85,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -122,6 +121,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -185,10 +185,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
@@ -15,7 +15,6 @@ CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F100C8=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=2000
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
@@ -29,6 +28,7 @@ CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=316
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=2
|
||||
CONFIG_MM_FILL_ALLOCATIONS=y
|
||||
CONFIG_MM_SMALL=y
|
||||
CONFIG_NAME_MAX=12
|
||||
|
||||
@@ -14,8 +14,6 @@ CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_IMU_ST_LSM9DS1=y
|
||||
CONFIG_DRIVERS_LINUX_PWM_OUT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_LSM9DS1_MAG=y
|
||||
CONFIG_DRIVERS_PWM_OUT_SIM=y
|
||||
@@ -26,7 +24,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
@@ -50,6 +47,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
|
||||
@@ -34,14 +34,12 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0016
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FreeFly RTK GPS"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -106,6 +104,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -138,6 +138,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
@@ -31,7 +31,6 @@ CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
@@ -94,6 +93,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -162,6 +162,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
@@ -18,7 +18,6 @@ CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -11,18 +11,6 @@ icm20689 -R 2 -s start
|
||||
bmi088 -A -R 2 -s start
|
||||
bmi088 -G -R 2 -s start
|
||||
|
||||
if ver hwtypecmp VD00
|
||||
then
|
||||
# Internal SPI BMI088
|
||||
bmi088 -A -R 2 -s start
|
||||
bmi088 -G -R 2 -s start
|
||||
fi
|
||||
if ver hwtypecmp VD01
|
||||
then
|
||||
# Internal SPI ICM-20602
|
||||
icm20602 -R 2 -s start
|
||||
fi
|
||||
|
||||
# internal compass
|
||||
ist8310 -I -R 10 start
|
||||
|
||||
|
||||
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004b
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL Holybro Durandal Vx"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
|
||||
@@ -46,7 +46,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004b
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 DurandalV1"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -89,6 +88,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -122,6 +122,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -162,11 +162,6 @@
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2
|
||||
|
||||
#define VD00 HW_VER_REV(0x0,0x0) // Durandal, Ver 0 Rev 0
|
||||
#define VD01 HW_VER_REV(0x0,0x1) // Durandal, Ver 0 Rev 1
|
||||
|
||||
/* CAN Silence
|
||||
*
|
||||
* Silent mode control \ ESC Mux select
|
||||
|
||||
@@ -264,6 +264,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
@@ -82,9 +82,7 @@ static const px4_hw_mft_item_t hw_mft_list_durandal[] = {
|
||||
};
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver_rev
|
||||
{VD00, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
{VD01, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
{0x0000, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020, 2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2020 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
|
||||
@@ -35,52 +35,28 @@
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
|
||||
initSPIHWVersion(HW_VER_REV(0, 0), {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortG, GPIO::Pin10}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortH, GPIO::Pin5}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortF, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI5, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin4}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin6}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin7}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin8})
|
||||
}),
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortG, GPIO::Pin10}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortH, GPIO::Pin5}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5})
|
||||
}),
|
||||
initSPIHWVersion(HW_VER_REV(0, 1), {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}),
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortH, GPIO::Pin5}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortF, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI5, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin4}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin6}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin7}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin8})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortF, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI5, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin4}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin6}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin7}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin8})
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
|
||||
@@ -38,7 +38,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -46,7 +45,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0016
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 KakuteF7"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -77,7 +75,6 @@ CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS=y
|
||||
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -90,8 +87,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
@@ -124,6 +123,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -222,6 +222,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
if (!spi_dev) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
led_on(LED_BLUE);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SPI interface to the MMCSD driver */
|
||||
@@ -230,6 +231,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
if (result != OK) {
|
||||
led_on(LED_BLUE);
|
||||
syslog(LOG_ERR, "[boot] FAILED to bind SPI port 1 to the MMCSD driver\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
up_udelay(20);
|
||||
@@ -248,6 +250,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
Binary file not shown.
@@ -39,7 +39,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -47,7 +46,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004E
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 PIX32V5"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -74,7 +72,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -87,8 +84,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -121,6 +120,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -272,6 +272,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004b
|
||||
CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
|
||||
@@ -37,7 +37,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
@@ -45,7 +44,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0036
|
||||
CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -88,6 +86,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
|
||||
@@ -170,6 +170,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_BLUE);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -38,7 +38,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -46,7 +45,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0xa32f
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU ModalAI FCv1"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -73,7 +71,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -86,8 +83,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -120,6 +119,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -277,6 +277,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0xa330
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL ModalAI FCv2"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -52,6 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LIB_BOARDCTL=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=8
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
@@ -38,7 +38,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95751
|
||||
@@ -46,7 +45,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0xa330
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU ModalAI FCv2"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -74,7 +72,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -89,8 +86,10 @@ CONFIG_IOB_NCHAINS=24
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -122,6 +121,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -252,6 +252,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
@@ -38,7 +38,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -46,7 +45,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x008D
|
||||
CONFIG_CDCACM_PRODUCTSTR="mRoControlZeroF7"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -73,7 +71,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -86,8 +83,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -120,6 +119,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -226,6 +226,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
@@ -38,7 +38,6 @@ CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
@@ -46,7 +45,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x008D
|
||||
CONFIG_CDCACM_PRODUCTSTR="mRoControlZeroF7"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -73,7 +71,6 @@ CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
@@ -86,8 +83,10 @@ CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -120,6 +119,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -226,6 +226,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,6 @@ CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1023
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL mRo ControlZeroH7 OEM"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
|
||||
@@ -46,7 +46,6 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1024
|
||||
CONFIG_CDCACM_PRODUCTSTR="mRoControlZeroH7 OEM"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
@@ -90,6 +89,7 @@ CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
@@ -123,6 +123,7 @@ CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
CONFIG_MODULES_MICRORTPS_BRIDGE=y
|
||||
@@ -186,10 +186,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user