forked from Archive/PX4-Autopilot
px4_fmu-v5_stackcheck: update stack sizes and add to Jenkins
- increase stack sizes to run cleanly under stackcheck - this is likely overkill for most boards, but using stackcheck to set our minimum ensures we have a very safe margin on regular builds and it's something we can currently afford - remove holybro_durandal-v1_stackcheck from test rack (there's only one unit)
This commit is contained in:
parent
7b4f6b6918
commit
66eacd24bc
|
@ -509,6 +509,81 @@ pipeline {
|
|||
}
|
||||
}
|
||||
|
||||
stage("px4_fmu-v5_stackcheck") {
|
||||
stages {
|
||||
stage("build px4_fmu-v5_stackcheck") {
|
||||
agent {
|
||||
docker {
|
||||
image 'px4io/px4-dev-nuttx-bionic:2020-04-01'
|
||||
args '-e CCACHE_BASEDIR=$WORKSPACE -v ${CCACHE_DIR}:${CCACHE_DIR}:rw'
|
||||
}
|
||||
}
|
||||
steps {
|
||||
sh 'export'
|
||||
sh 'make distclean'
|
||||
sh 'ccache -s'
|
||||
sh 'git fetch --tags'
|
||||
sh 'make px4_fmu-v5_stackcheck'
|
||||
sh 'make sizes'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf', name: 'px4_fmu-v5_stackcheck'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh 'make distclean'
|
||||
}
|
||||
}
|
||||
} // stage build
|
||||
stage("test") {
|
||||
agent {
|
||||
label 'px4_fmu-v5'
|
||||
}
|
||||
stages {
|
||||
stage("flash") {
|
||||
steps {
|
||||
sh 'export'
|
||||
sh 'find /dev/serial'
|
||||
unstash 'px4_fmu-v5_stackcheck'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf'
|
||||
sh './Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-FTDI_*` --baudrate 57600'
|
||||
}
|
||||
}
|
||||
stage("configure") {
|
||||
steps {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set IMU_GYRO_RATEMAX 250"' // limit cpu usage
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set MAV_0_CONFIG 0"' // limit cpu usage
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001"' // generic multicopter
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
stage("status") {
|
||||
steps {
|
||||
statusFTDI()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
steps {
|
||||
// run tests
|
||||
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *usb-FTDI_*`'
|
||||
}
|
||||
}
|
||||
stage("reset") {
|
||||
steps {
|
||||
cleanupFTDI();
|
||||
}
|
||||
}
|
||||
}
|
||||
options {
|
||||
timeout(time: 60, unit: 'MINUTES')
|
||||
}
|
||||
} // stage test
|
||||
}
|
||||
}
|
||||
|
||||
stage("modalai_fc-v1_default") {
|
||||
stages {
|
||||
stage("build modalai_fc-v1_default") {
|
||||
|
@ -656,93 +731,6 @@ pipeline {
|
|||
}
|
||||
}
|
||||
|
||||
stage("holybro_durandal-v1_stackcheck") {
|
||||
stages {
|
||||
stage("build holybro_durandal-v1_stackcheck") {
|
||||
agent {
|
||||
docker {
|
||||
image 'px4io/px4-dev-nuttx-bionic:2020-04-01'
|
||||
args '-e CCACHE_BASEDIR=$WORKSPACE -v ${CCACHE_DIR}:${CCACHE_DIR}:rw'
|
||||
}
|
||||
}
|
||||
steps {
|
||||
sh 'export'
|
||||
sh 'make distclean'
|
||||
sh 'ccache -s'
|
||||
sh 'git fetch --tags'
|
||||
sh 'make holybro_durandal-v1_stackcheck'
|
||||
sh 'make sizes'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/holybro_durandal-v1_stackcheck/holybro_durandal-v1_stackcheck.elf', name: 'holybro_durandal-v1_stackcheck'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
sh 'make distclean'
|
||||
}
|
||||
}
|
||||
} // stage build
|
||||
stage("test") {
|
||||
agent {
|
||||
label 'holybro_durandal-v1'
|
||||
}
|
||||
stages {
|
||||
stage("flash") {
|
||||
steps {
|
||||
sh 'export'
|
||||
sh 'find /dev/serial'
|
||||
unstash 'holybro_durandal-v1_stackcheck'
|
||||
// flash board and watch bootup
|
||||
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/holybro_durandal-v1_stackcheck/holybro_durandal-v1_stackcheck.elf'
|
||||
sh './Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-FTDI_*` --baudrate 57600'
|
||||
}
|
||||
}
|
||||
stage("configure") {
|
||||
steps {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_BL_UPDATE 1"' // update bootloader
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
stage("status") {
|
||||
steps {
|
||||
statusFTDI()
|
||||
}
|
||||
}
|
||||
stage("tests") {
|
||||
steps {
|
||||
// run tests
|
||||
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *usb-FTDI_*`'
|
||||
}
|
||||
}
|
||||
stage("stop modules") {
|
||||
steps {
|
||||
// manually stop everything
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink stop-all"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ekf2 stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "navigator stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dataman stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "fmu stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "px4io stop"'
|
||||
}
|
||||
}
|
||||
stage("reset") {
|
||||
steps {
|
||||
cleanupFTDI();
|
||||
}
|
||||
}
|
||||
}
|
||||
options {
|
||||
timeout(time: 60, unit: 'MINUTES')
|
||||
}
|
||||
} // stage test
|
||||
}
|
||||
}
|
||||
|
||||
stage("nxp_fmuk66-v3_default") {
|
||||
stages {
|
||||
stage("build nxp_fmuk66-v3_default") {
|
||||
|
|
|
@ -244,5 +244,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -271,5 +271,5 @@ CONFIG_USART6_RXBUFSIZE=600
|
|||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -198,5 +198,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -105,5 +105,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="bootloader_main"
|
||||
|
|
|
@ -248,6 +248,6 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
|
|
|
@ -249,6 +249,6 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
|
|
|
@ -226,5 +226,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -204,5 +204,5 @@ CONFIG_USART6_RXDMA=y
|
|||
CONFIG_USART6_SERIAL_CONSOLE=y
|
||||
CONFIG_USART6_TXBUFSIZE=300
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -257,5 +257,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -245,5 +245,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -247,5 +247,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -243,5 +243,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -213,6 +213,6 @@ CONFIG_USBDEV_BUSPOWERED=y
|
|||
CONFIG_USBDEV_DUALSPEED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
|
|
|
@ -243,6 +243,6 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
|
|
|
@ -198,5 +198,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -249,5 +249,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -248,5 +248,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -249,5 +249,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -246,5 +246,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -247,5 +247,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -247,5 +247,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -251,5 +251,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -254,5 +254,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -253,5 +253,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -252,5 +252,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -253,5 +253,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -253,5 +253,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -67,6 +67,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
#esc_battery
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
|
|
|
@ -292,5 +292,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -293,5 +293,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -246,5 +246,5 @@ CONFIG_USBDEV=y
|
|||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2688
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
|
|
|
@ -48,21 +48,21 @@ struct wq_config_t {
|
|||
|
||||
namespace wq_configurations
|
||||
{
|
||||
static constexpr wq_config_t rate_ctrl{"wq:rate_ctrl", 1600, 0}; // PX4 inner loop highest priority
|
||||
static constexpr wq_config_t rate_ctrl{"wq:rate_ctrl", 1664, 0}; // PX4 inner loop highest priority
|
||||
|
||||
static constexpr wq_config_t SPI0{"wq:SPI0", 2368, -1};
|
||||
static constexpr wq_config_t SPI1{"wq:SPI1", 2368, -2};
|
||||
static constexpr wq_config_t SPI2{"wq:SPI2", 2368, -3};
|
||||
static constexpr wq_config_t SPI3{"wq:SPI3", 2368, -4};
|
||||
static constexpr wq_config_t SPI4{"wq:SPI4", 2368, -5};
|
||||
static constexpr wq_config_t SPI5{"wq:SPI5", 2368, -6};
|
||||
static constexpr wq_config_t SPI6{"wq:SPI6", 2368, -7};
|
||||
static constexpr wq_config_t SPI0{"wq:SPI0", 2496, -1};
|
||||
static constexpr wq_config_t SPI1{"wq:SPI1", 2496, -2};
|
||||
static constexpr wq_config_t SPI2{"wq:SPI2", 2496, -3};
|
||||
static constexpr wq_config_t SPI3{"wq:SPI3", 2496, -4};
|
||||
static constexpr wq_config_t SPI4{"wq:SPI4", 2496, -5};
|
||||
static constexpr wq_config_t SPI5{"wq:SPI5", 2496, -6};
|
||||
static constexpr wq_config_t SPI6{"wq:SPI6", 2496, -7};
|
||||
|
||||
static constexpr wq_config_t I2C0{"wq:I2C0", 1400, -8};
|
||||
static constexpr wq_config_t I2C1{"wq:I2C1", 1400, -9};
|
||||
static constexpr wq_config_t I2C2{"wq:I2C2", 1400, -10};
|
||||
static constexpr wq_config_t I2C3{"wq:I2C3", 1400, -11};
|
||||
static constexpr wq_config_t I2C4{"wq:I2C4", 1400, -12};
|
||||
static constexpr wq_config_t I2C0{"wq:I2C0", 1472, -8};
|
||||
static constexpr wq_config_t I2C1{"wq:I2C1", 1472, -9};
|
||||
static constexpr wq_config_t I2C2{"wq:I2C2", 1472, -10};
|
||||
static constexpr wq_config_t I2C3{"wq:I2C3", 1472, -11};
|
||||
static constexpr wq_config_t I2C4{"wq:I2C4", 1472, -12};
|
||||
|
||||
// PX4 att/pos controllers, highest priority after sensors.
|
||||
static constexpr wq_config_t att_pos_ctrl{"wq:att_pos_ctrl", 7200, -13};
|
||||
|
|
Loading…
Reference in New Issue