forked from Archive/PX4-Autopilot
1042 lines
54 KiB
Groovy
1042 lines
54 KiB
Groovy
#!/usr/bin/env groovy
|
|
|
|
pipeline {
|
|
agent none
|
|
stages {
|
|
stage('Hardware Test') {
|
|
|
|
parallel {
|
|
|
|
// stage("px4_fmu-v2_test") {
|
|
// stages {
|
|
// stage("build px4_fmu-v2_test") {
|
|
// agent {
|
|
// docker {
|
|
// image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
// 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-v2_test'
|
|
// sh 'make sizes'
|
|
// sh 'ccache -s'
|
|
// stash includes: 'build/px4_fmu-v2_test/px4_fmu-v2_test.elf', name: 'px4_fmu-v2_test'
|
|
// }
|
|
// post {
|
|
// always {
|
|
// sh 'make distclean'
|
|
// }
|
|
// }
|
|
// } // stage build
|
|
// stage("test") {
|
|
// agent {
|
|
// label 'px4_fmu-v2'
|
|
// }
|
|
// stages {
|
|
// stage("flash") {
|
|
// steps {
|
|
// sh 'export'
|
|
// sh 'find /dev/serial'
|
|
// unstash 'px4_fmu-v2_test'
|
|
// // flash board and watch bootup
|
|
// sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v2_test/px4_fmu-v2_test.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-FTDI_*` --baudrate 57600'
|
|
// }
|
|
// }
|
|
// stage("reset") {
|
|
// steps {
|
|
// cleanupFTDI();
|
|
// }
|
|
// }
|
|
// }
|
|
// options {
|
|
// timeout(time: 90, unit: 'MINUTES')
|
|
// }
|
|
// }
|
|
// }
|
|
// }
|
|
|
|
stage("px4_fmu-v3_default") {
|
|
stages {
|
|
stage("build px4_fmu-v3_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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-v3_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v3_default/px4_fmu-v3_default.elf', name: 'px4_fmu-v3_default'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'px4_fmu-v3'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
unstash 'px4_fmu-v3_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v3_default/px4_fmu-v3_default.elf && ./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_AUTOCONFIG 2"'
|
|
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 save"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "px4io forceupdate 14662 /etc/extras/px4_io-v2_default.bin" || true' // force px4io update
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v4_default") {
|
|
stages {
|
|
stage("build px4_fmu-v4_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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-v4_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v4_default/px4_fmu-v4_default.elf', name: 'px4_fmu-v4_default'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'px4_fmu-v4'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
unstash 'px4_fmu-v4_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4_default/px4_fmu-v4_default.elf && ./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_AUTOCONFIG 2"'
|
|
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" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v4pro_default") {
|
|
stages {
|
|
stage("build px4_fmu-v4pro_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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-v4pro_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v4pro_default/px4_fmu-v4pro_default.elf', name: 'px4_fmu-v4pro_default'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'px4_fmu-v4pro'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
unstash 'px4_fmu-v4pro_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v4pro_default/px4_fmu-v4pro_default.elf && ./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_AUTOCONFIG 2"'
|
|
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 save"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "px4io forceupdate 14662 /etc/extras/px4_io-v2_default.bin" || true' // force px4io update
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v5_default") {
|
|
stages {
|
|
stage("build px4_fmu-v5_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v5_default/px4_fmu-v5_default.elf', name: 'px4_fmu-v5_default'
|
|
}
|
|
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_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_default/px4_fmu-v5_default.elf && ./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_AUTOCONFIG 2"'
|
|
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 IMU_GYRO_RATEMAX 2000"'
|
|
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 "px4io forceupdate 14662 /etc/extras/px4_io-v2_default.bin" || true' // force px4io update
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v5_debug") {
|
|
stages {
|
|
stage("build px4_fmu-v5_debug") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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_debug'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v5_debug/px4_fmu-v5_debug.elf', name: 'px4_fmu-v5_debug'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'px4_fmu-v5'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001" || true' // generic multicopter
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set IMU_GYRO_RATEMAX 250" || true'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save" || true'
|
|
unstash 'px4_fmu-v5_debug'
|
|
// 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-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 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 "px4io forceupdate 14662 /etc/extras/px4_io-v2_default.bin" || true' // force px4io update
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v5_optimized") {
|
|
stages {
|
|
stage("build px4_fmu-v5_optimized") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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_optimized'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/px4_fmu-v5_optimized/px4_fmu-v5_optimized.elf', name: 'px4_fmu-v5_optimized'
|
|
}
|
|
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_optimized'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/px4_fmu-v5_optimized/px4_fmu-v5_optimized.elf && ./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_AUTOCONFIG 2"'
|
|
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 save"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("px4_fmu-v5_stackcheck") {
|
|
stages {
|
|
stage("build px4_fmu-v5_stackcheck") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001" || true' // generic multicopter
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set IMU_GYRO_RATEMAX 250" || true'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save" || true'
|
|
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 && ./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" || true' // 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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("modalai_fc-v1_default") {
|
|
stages {
|
|
stage("build modalai_fc-v1_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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 modalai_fc-v1_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/modalai_fc-v1_default/modalai_fc-v1_default.elf', name: 'modalai_fc-v1_default'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'modalai_fc-v1'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
unstash 'modalai_fc-v1_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/modalai_fc-v1_default/modalai_fc-v1_default.elf && ./Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *usb-SEGGER_*` --baudrate 57600'
|
|
}
|
|
}
|
|
stage("configure") {
|
|
steps {
|
|
// configure
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set SYS_AUTOCONFIG 2"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set SYS_AUTOSTART 4001"' // generic vtol standardulticopter
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param save"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "reboot" || true' // reboot to apply
|
|
}
|
|
}
|
|
stage("status") {
|
|
steps {
|
|
statusSEGGER()
|
|
}
|
|
}
|
|
stage("tests") {
|
|
steps {
|
|
// run tests
|
|
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *usb-SEGGER_*`'
|
|
}
|
|
}
|
|
stage("reset") {
|
|
steps {
|
|
cleanupSEGGER()
|
|
}
|
|
}
|
|
}
|
|
options {
|
|
timeout(time: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("holybro_durandal-v1_default") {
|
|
stages {
|
|
stage("build holybro_durandal-v1_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/holybro_durandal-v1_default/holybro_durandal-v1_default.elf', name: 'holybro_durandal-v1_default'
|
|
}
|
|
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_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/holybro_durandal-v1_default/holybro_durandal-v1_default.elf && ./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 DSHOT_CONFIG 600"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set IMU_GYRO_RATEMAX 4000"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOCONFIG 2"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001"' // generic quadcopter
|
|
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 set SYS_USE_IO 0"' // for dshot
|
|
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 "px4io forceupdate 14662 /etc/extras/px4_io-v2_default.bin" || true' // force px4io update
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true' // reboot to apply
|
|
}
|
|
}
|
|
stage("status") {
|
|
steps {
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dshot status"'
|
|
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: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
stage("nxp_fmuk66-v3_default") {
|
|
stages {
|
|
stage("build nxp_fmuk66-v3_default") {
|
|
agent {
|
|
docker {
|
|
image 'px4io/px4-dev-nuttx-focal:2020-09-14'
|
|
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 nxp_fmuk66-v3_default'
|
|
sh 'make sizes'
|
|
sh 'ccache -s'
|
|
stash includes: 'build/nxp_fmuk66-v3_default/nxp_fmuk66-v3_default.elf', name: 'nxp_fmuk66-v3_default'
|
|
}
|
|
post {
|
|
always {
|
|
sh 'make distclean'
|
|
}
|
|
}
|
|
} // stage build
|
|
stage("test") {
|
|
agent {
|
|
label 'nxp_fmuk66-v3'
|
|
}
|
|
stages {
|
|
stage("flash") {
|
|
steps {
|
|
sh 'export'
|
|
sh 'find /dev/serial'
|
|
unstash 'nxp_fmuk66-v3_default'
|
|
// flash board and watch bootup
|
|
sh './platforms/nuttx/Debug/upload_jlink_gdb.sh build/nxp_fmuk66-v3_default/nxp_fmuk66-v3_default.elf && ./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_AUTOCONFIG 2"'
|
|
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" || true' // 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_*` || true' // allow failure due to intermittent serial console issues
|
|
}
|
|
}
|
|
stage("reset") {
|
|
steps {
|
|
cleanupFTDI();
|
|
}
|
|
}
|
|
}
|
|
options {
|
|
timeout(time: 90, unit: 'MINUTES')
|
|
}
|
|
} // stage test
|
|
}
|
|
}
|
|
|
|
} // parallel
|
|
} // stage Hardware Test
|
|
} // stages
|
|
environment {
|
|
CCACHE_DIR = '/tmp/ccache'
|
|
CI = true
|
|
}
|
|
options {
|
|
buildDiscarder(logRotator(numToKeepStr: '20', artifactDaysToKeepStr: '40'))
|
|
timeout(time: 90, unit: 'MINUTES')
|
|
}
|
|
}
|
|
|
|
void statusFTDI() {
|
|
// run logger
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger on"'
|
|
// status commands
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "free"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "work_queue status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "board_adc test"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander check"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate accel quick; sleep 2; param show CAL_ACC*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate mag quick; sleep 2; param show CAL_MAG*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dataman status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "df"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dmesg"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "gps status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener adc_report"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener battery_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener cpuload"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_attitude"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_local_position"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_selector_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_sensor_bias"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener estimator_status_flags"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener logger_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_fifo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_baro"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_combined"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro_fifo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_mag"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensors_status_imu"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener px4io_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener system_power"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_air_data"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_angular_acceleration"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_angular_velocity"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_attitude"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_imu"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_imu_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_local_position"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_magnetometer"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /dev"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /etc"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /obj"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /proc"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "cat /proc/meminfo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "cat /proc/uptime"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink status streams"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mount"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mtd status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param show"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "perf latency"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "perf"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ps"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "pwm info -d /dev/pwm_output0"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "pwm info -d /dev/pwm_output1"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "pwm_out status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "px4io status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "sd_bench -r 2"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "sensors status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener cpuload; top once; listener cpuload"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "uorb status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "uorb top -1 -a"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ver all"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "work_queue status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ekf2 status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "free"'
|
|
// stop logger
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger off"'
|
|
}
|
|
|
|
void statusSEGGER() {
|
|
// run logger
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger on"'
|
|
// status commands
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "free"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "work_queue status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "board_adc test"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander check"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate accel quick; sleep 2; param show CAL_ACC*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate mag quick; sleep 2; param show CAL_MAG*"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dataman status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "df -h"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dmesg"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "gps status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener adc_report"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener battery_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener cpuload"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_attitude"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_local_position"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_selector_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_sensor_bias"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener estimator_status_flags"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener logger_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_fifo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_baro"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_combined"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro_fifo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_mag"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensors_status_imu"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener px4io_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener system_power"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_air_data"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_angular_acceleration"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_angular_velocity"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_attitude"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_imu"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_imu_status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_local_position"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_magnetometer"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /dev"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /etc"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /obj"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /proc"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "cat /proc/meminfo"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "cat /proc/uptime"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink status streams"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mount"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mtd status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param show"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "perf latency"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "perf"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ps"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "pwm info -d /dev/pwm_output0"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "pwm info -d /dev/pwm_output1"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "pwm_out status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "px4io status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "sd_bench -r 2"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "sensors status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener cpuload; top once; listener cpuload"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "uorb status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "uorb top -1 -a"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ver all"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "work_queue status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ekf2 status"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "free"'
|
|
// stop logger
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger off"'
|
|
}
|
|
|
|
void cleanupFTDI() {
|
|
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 "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 off"'
|
|
|
|
// wipe sdcard
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "umount /fs/microsd"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mkfatfs /dev/mmcsd0"'
|
|
|
|
// drop any uncommited hardfaults
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "hardfault_log rearm"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "hardfault_log reset"'
|
|
|
|
// erase mtd
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mtd readtest"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mtd rwtest"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mtd erase"'
|
|
|
|
// disable buzzer and cleanup storage
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param reset_all"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SDLOG_DIRS_MAX 1"'
|
|
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 "param status"'
|
|
|
|
// reboot
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot" || true'
|
|
}
|
|
|
|
void cleanupSEGGER() {
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander stop"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink stop-all"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "navigator stop"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dataman stop"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger off"'
|
|
|
|
// wipe sdcard
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "umount /fs/microsd"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mkfatfs /dev/mmcsd0"'
|
|
|
|
// drop any uncommited hardfaults
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "hardfault_log rearm"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "hardfault_log reset"'
|
|
|
|
// erase mtd
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mtd readtest"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mtd rwtest"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mtd erase"'
|
|
|
|
// disable buzzer and cleanup storage
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param reset_all"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set CBRK_BUZZER 782097"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set SDLOG_DIRS_MAX 1"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param save"'
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param status"'
|
|
|
|
// reboot
|
|
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "reboot" || true'
|
|
}
|