Compare commits

..

1 Commits

Author SHA1 Message Date
Daniel Agar f23740a3c5 parameters: add boolean support (PARAM_DEFINE_BOOL)
- real boolean parameter support saves a bit of space in export (bson)
and in mavlink sync
2021-12-23 17:08:12 -05:00
272 changed files with 2626 additions and 6466 deletions
+2 -2
View File
@@ -170,7 +170,7 @@ def createBuildNode(Boolean archive, String docker_image, String target) {
try {
sh('export')
checkout(scm)
sh('make distclean; git clean -ff -x -d .')
sh('make distclean')
sh('git fetch --tags')
sh('ccache -s')
sh('make ' + target)
@@ -187,7 +187,7 @@ def createBuildNode(Boolean archive, String docker_image, String target) {
throw (exc)
}
finally {
sh('make distclean; git clean -ff -x -d .')
sh('make distclean')
}
}
}
+72 -58
View File
@@ -25,7 +25,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -73,11 +73,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/cubepilot_cubeorange_test/cubepilot_cubeorange_test.elf || true'
}
}
} // stage test
@@ -102,7 +99,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -145,11 +142,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/cuav_x7pro_test/cuav_x7pro_test.elf || true'
}
}
} // stage test
@@ -174,7 +168,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -217,11 +211,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v3_test/px4_fmu-v3_test.elf || true'
}
}
} // stage test
@@ -246,7 +237,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -288,11 +279,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v4_test/px4_fmu-v4_test.elf || true'
}
}
} // stage test
@@ -317,7 +305,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -360,11 +348,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v4pro_test/px4_fmu-v4pro_test.elf || true'
}
}
} // stage test
@@ -389,7 +374,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -422,7 +407,7 @@ pipeline {
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"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -u -v" || true'
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
@@ -441,6 +426,7 @@ pipeline {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set IMU_GYRO_RATEMAX 200" || true' // limit cpu usage
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
checkStatus()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
}
@@ -452,11 +438,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v5_debug/px4_fmu-v5_debug.elf || true'
}
}
} // stage test
@@ -481,7 +464,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -525,6 +508,7 @@ pipeline {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set IMU_GYRO_RATEMAX 200" || true' // limit cpu usage
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
checkStatus()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
}
@@ -536,11 +520,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v5_stackcheck/px4_fmu-v5_stackcheck.elf || true'
}
}
} // stage test
@@ -565,7 +546,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -608,11 +589,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/px4_fmu-v5_test/px4_fmu-v5_test.elf || true'
}
}
} // stage test
@@ -637,7 +615,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
} // stage build
@@ -680,11 +658,8 @@ pipeline {
}
}
post {
failure {
sh 'cat /tmp/pyserial_spy_file.txt'
}
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_simple.sh build/nxp_fmuk66-v3_test/nxp_fmuk66-v3_test.elf || true'
}
}
} // stage test
@@ -710,7 +685,7 @@ void checkoutSCM() {
retry(3) {
checkout scm
sh 'export'
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
sh 'git fetch --tags'
sh 'ccache -z'
}
@@ -747,33 +722,26 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SYS*"'
// run logger
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger on"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger on" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sleep 1"' // sleep before continuing
// status commands
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/mount"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/usage"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/meminfo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/uptime"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander check" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ekf2 status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "free"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gps status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload; top once; listener cpuload"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /bin"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /dev"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /etc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /obj"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink status streams" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount"'
@@ -794,7 +762,7 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ver all"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"'
// stop logger
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger off"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger off" || true'
}
void resetParameters() {
@@ -851,7 +819,24 @@ void runTests() {
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"'
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
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/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/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() {
@@ -951,6 +936,10 @@ void printTopics() {
}
void resetBoard() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd" || true'
resetParameters()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param set SYS_AUTOSTART 0" || true'
@@ -960,4 +949,29 @@ void resetBoard() {
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
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs" || true'
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'
// format
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman stop" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "umount /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mkfatfs -F 32 /dev/mmcsd0" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount -t vfat /dev/mmcsd0 /fs/microsd" || true'
// check SD card
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df -h" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ls /proc/fs" || true'
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
}
Vendored
+12 -12
View File
@@ -88,7 +88,7 @@ pipeline {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
sh 'git fetch --all --tags'
sh 'make airframe_metadata'
dir('build/px4_sitl_default/docs') {
@@ -98,7 +98,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
}
@@ -108,7 +108,7 @@ pipeline {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
sh 'git fetch --all --tags'
sh 'make parameters_metadata'
dir('build/px4_sitl_default/docs') {
@@ -118,7 +118,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
}
@@ -128,7 +128,7 @@ pipeline {
docker { image 'px4io/px4-dev-base-focal:2021-08-18' }
}
steps {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
sh 'git fetch --all --tags'
sh 'make module_documentation'
dir('build/px4_sitl_default/docs') {
@@ -138,7 +138,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
}
@@ -156,7 +156,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
}
@@ -170,7 +170,7 @@ pipeline {
}
steps {
sh 'export'
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
sh 'git fetch --all --tags'
sh 'make uorb_graphs'
dir('Tools/uorb_graph') {
@@ -180,7 +180,7 @@ pipeline {
}
post {
always {
sh 'make distclean; git clean -ff -x -d .'
sh 'make distclean'
}
}
}
@@ -261,7 +261,7 @@ pipeline {
steps {
sh('export')
sh('git fetch --all --tags')
sh('make distclean; git clean -ff -x -d .')
sh('make distclean')
sh('make px4_sitl_rtps')
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/micrortps_agent.git -b ${BRANCH_NAME}")
@@ -290,7 +290,7 @@ pipeline {
}
steps {
sh('export')
sh('make distclean; git clean -ff -x -d .')
sh('make distclean')
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git")
// 'master' branch
@@ -319,7 +319,7 @@ pipeline {
}
steps {
sh('export')
sh('make distclean; git clean -ff -x -d .')
sh('make distclean')
withCredentials([usernamePassword(credentialsId: 'px4buildbot_github_personal_token', passwordVariable: 'GIT_PASS', usernameVariable: 'GIT_USER')]) {
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_ros_com.git -b ${BRANCH_NAME}")
// deploy uORB RTPS ID map
+1 -3
View File
@@ -482,9 +482,7 @@ shellcheck_all:
@make px4_fmu-v5_default shellcheck
validate_module_configs:
@find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f \
-not -path "$(SRC_DIR)/src/lib/mixer_module/*" -not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \
xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml
@find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f -not -path "$(SRC_DIR)/src/lib/mixer_module/*" -print0 | xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml
# Cleanup
# --------------------------------------------------------------------
@@ -14,19 +14,19 @@ param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_MC_R_COUNT 4
param set-default CA_MC_R0_PX 0.1515
param set-default CA_MC_R0_PY 0.245
param set-default CA_MC_R0_KM 0.05
param set-default CA_MC_R1_PX -0.1515
param set-default CA_MC_R1_PY -0.1875
param set-default CA_MC_R1_KM 0.05
param set-default CA_MC_R2_PX 0.1515
param set-default CA_MC_R2_PY -0.245
param set-default CA_MC_R2_KM -0.05
param set-default CA_MC_R3_PX -0.1515
param set-default CA_MC_R3_PY 0.1875
param set-default CA_MC_R3_KM -0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
@@ -8,63 +8,6 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 7
param set-default CA_ROTOR_COUNT 8
param set-default CA_R_REV 255
param set-default CA_ROTOR0_AX 1.0000
param set-default CA_ROTOR0_AY -1.0000
param set-default CA_ROTOR0_AZ 0.0000
param set-default CA_ROTOR0_KM 0.0000
param set-default CA_ROTOR0_PX 0.5000
param set-default CA_ROTOR0_PY 0.3000
param set-default CA_ROTOR0_PZ 0.2000
param set-default CA_ROTOR1_AX 1.0000
param set-default CA_ROTOR1_AY 1.0000
param set-default CA_ROTOR1_AZ 0.0000
param set-default CA_ROTOR1_KM 0.0000
param set-default CA_ROTOR1_PX 0.5000
param set-default CA_ROTOR1_PY -0.3000
param set-default CA_ROTOR1_PZ 0.2000
param set-default CA_ROTOR2_AX 1.0000
param set-default CA_ROTOR2_AY 1.0000
param set-default CA_ROTOR2_AZ 0.0000
param set-default CA_ROTOR2_KM 0.0000
param set-default CA_ROTOR2_PX -0.5000
param set-default CA_ROTOR2_PY 0.3000
param set-default CA_ROTOR2_PZ 0.2000
param set-default CA_ROTOR3_AX 1.0000
param set-default CA_ROTOR3_AY -1.0000
param set-default CA_ROTOR3_AZ 0.0000
param set-default CA_ROTOR3_KM 0.0000
param set-default CA_ROTOR3_PX -0.5000
param set-default CA_ROTOR3_PY -0.3000
param set-default CA_ROTOR3_PZ 0.2000
param set-default CA_ROTOR4_AZ -1.0000
param set-default CA_ROTOR4_KM 0.0000
param set-default CA_ROTOR4_PX 0.5000
param set-default CA_ROTOR4_PY 0.5000
param set-default CA_ROTOR5_AZ 1.0000
param set-default CA_ROTOR5_KM 0.0000
param set-default CA_ROTOR5_PX 0.5000
param set-default CA_ROTOR5_PY -0.5000
param set-default CA_ROTOR6_AZ 1.0000
param set-default CA_ROTOR6_KM 0.0000
param set-default CA_ROTOR6_PX -0.5000
param set-default CA_ROTOR6_PY 0.5000
param set-default CA_ROTOR7_KM 0.0000
param set-default CA_ROTOR7_PX -0.5000
param set-default CA_ROTOR7_PY -0.5000
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108
set MIXER skip
set PWM_OUT 12345678
set MIXER_FILE etc/mixers-sitl/vectored6dof_sitl.main.mix
set MIXER custom
@@ -43,32 +43,5 @@ param set-default NAV_DLL_ACT 2
param set-default RWTO_TKOFF 1
#param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 1
param set-default CA_ROTOR_COUNT 1
param set-default CA_ROTOR0_PX 0.3
param set-default CA_SV_CS_COUNT 6
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS3_TRQ_Y 1.0
param set-default CA_SV_CS3_TYPE 4
param set-default CA_SV_CS4_TYPE 9
param set-default CA_SV_CS5_TYPE 10
param set-default PWM_MAIN_FUNC3 204
param set-default PWM_MAIN_FUNC4 205
param set-default PWM_MAIN_FUNC5 101
param set-default PWM_MAIN_FUNC6 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
set MIXER custom
@@ -7,39 +7,6 @@
. ${R}etc/init.d/rc.vtol_defaults
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 2
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default FW_L1_PERIOD 12
param set-default FW_MAN_P_MAX 30
param set-default FW_PR_FF 0.2
@@ -7,48 +7,14 @@
. ${R}etc/init.d/rc.vtol_defaults
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 1
param set-default CA_ROTOR0_PY 2
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -1
param set-default CA_ROTOR1_PY -1
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 1
param set-default CA_ROTOR2_PY -1
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default CA_ROTOR3_KM -0.05
param set-default CA_SV_CS_COUNT 2
param set-default CA_SV_CS0_TYPE 5
param set-default CA_SV_CS0_TRQ_P 0.5
param set-default CA_SV_CS0_TRQ_Y -0.5
param set-default CA_SV_CS1_TYPE 6
param set-default CA_SV_CS1_TRQ_P 0.5
param set-default CA_SV_CS1_TRQ_Y 0.5
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 0
param set-default PWM_MAIN_FUNC6 201
param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_REV 96 # invert both elevons
param set-default FW_L1_PERIOD 12
param set-default FW_MAN_P_MAX 30
param set-default FW_PR_I 0.2
param set-default FW_PR_P 0.2
param set-default FW_PR_P 0.3
param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MAX 32
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_P 0.2
param set-default FW_RR_P 0.3
param set-default FW_THR_CRUISE 0.33
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
@@ -70,8 +36,6 @@ param set-default MPC_XY_VEL_D_ACC 0.1
param set-default NAV_ACC_RAD 5
param set-default NAV_LOITER_RAD 80
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_SC 0.5
param set-default VT_F_TRANS_DUR 1.5
param set-default VT_F_TRANS_THR 0.7
param set-default VT_TYPE 0
@@ -7,52 +7,6 @@
. ${R}etc/init.d/rc.vtol_defaults
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 3
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR0_TILT 1
param set-default CA_ROTOR1_TILT 2
param set-default CA_ROTOR2_TILT 3
param set-default CA_ROTOR3_TILT 4
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_TL0_CT 0
param set-default CA_SV_TL1_CT 0
param set-default CA_SV_TL2_CT 0
param set-default CA_SV_TL3_CT 0
param set-default CA_SV_TL_COUNT 4
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 204
param set-default PWM_MAIN_FUNC6 205
param set-default PWM_MAIN_FUNC7 206
param set-default PWM_MAIN_FUNC8 207
param set-default PWM_MAIN_FUNC9 201
param set-default PWM_MAIN_FUNC10 202
param set-default PWM_MAIN_FUNC11 203
param set-default FW_L1_PERIOD 12
param set-default FW_MAN_P_MAX 30
param set-default FW_PR_FF 0.2
@@ -28,15 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128
param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 2.0
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 5
param set-default CA_R_REV 1
param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101
set MAV_TYPE 10
set MIXER_FILE skip
set MIXER_FILE etc/mixers-sitl/rover_ackermann_sitl.main.mix
@@ -28,15 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128
param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 2.0
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 6
param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 101
param set-default PWM_MAIN_FUNC6 102
param set-default PWM_MAIN_FUNC7 102
set MAV_TYPE 10
set MIXER_FILE skip
set MIXER_FILE etc/mixers-sitl/rover_diff_sitl.main.mix
@@ -28,25 +28,6 @@ param set-default CBRK_AIRSPD_CHK 162128
param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 2.0
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 9
param set-default CA_ROTOR_COUNT 2
param set-default CA_ROTOR0_AX 1
param set-default CA_ROTOR0_AZ 0
param set-default CA_ROTOR0_KM 0
param set-default CA_ROTOR0_PX -2
param set-default CA_ROTOR0_PY -1
param set-default CA_ROTOR1_AX 1
param set-default CA_ROTOR1_AZ 0
param set-default CA_ROTOR1_KM 0
param set-default CA_ROTOR1_PX -2
param set-default CA_ROTOR1_PY 1
param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
set MAV_TYPE 11
set MIXER skip
set MIXER_FILE etc/mixers-sitl/boat_sitl.main.mix
@@ -11,31 +11,5 @@
. ${R}etc/init.d/rc.airship_defaults
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 9
param set-default CA_ROTOR_COUNT 3
param set-default CA_ROTOR0_AX 1.0000
param set-default CA_ROTOR0_AZ 0.0000
param set-default CA_ROTOR0_KM 0.0000
param set-default CA_ROTOR0_PY 2.0000
param set-default CA_ROTOR1_AX 1.0000
param set-default CA_ROTOR1_AZ 0.0000
param set-default CA_ROTOR1_KM 0.0000
param set-default CA_ROTOR1_PY -2.0000
param set-default CA_ROTOR2_AY -1.0000
param set-default CA_ROTOR2_AZ 0.0000
param set-default CA_ROTOR2_KM 0.0000
param set-default CA_ROTOR2_PX -10.0000
param set-default CA_SV_CS_COUNT 1
param set-default CA_SV_CS0_TRQ_P 1.0000
param set-default CA_R_REV 7
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 201
param set-default PWM_MAIN_FUNC4 103
set MIXER skip
set MIXER cloudship
set PWM_OUT 1234
@@ -30,26 +30,26 @@ param set-default MNT_MODE_IN 0
param set-default MAV_PROTO_VER 2
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 6
param set-default CA_MC_R_COUNT 6
param set-default CA_ROTOR0_PX 0.0
param set-default CA_ROTOR0_PY 1.0
param set-default CA_ROTOR0_KM -0.05
param set-default CA_ROTOR1_PX 0.0
param set-default CA_ROTOR1_PY -1.0
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.866025
param set-default CA_ROTOR2_PY -0.5
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.866025
param set-default CA_ROTOR3_PY 0.5
param set-default CA_ROTOR3_KM 0.05
param set-default CA_ROTOR4_PX 0.866025
param set-default CA_ROTOR4_PY 0.5
param set-default CA_ROTOR4_KM 0.05
param set-default CA_ROTOR5_PX -0.866025
param set-default CA_ROTOR5_PY -0.5
param set-default CA_ROTOR5_KM -0.05
param set-default CA_MC_R0_PX 0.0
param set-default CA_MC_R0_PY 1.0
param set-default CA_MC_R0_KM -0.05
param set-default CA_MC_R1_PX 0.0
param set-default CA_MC_R1_PY -1.0
param set-default CA_MC_R1_KM 0.05
param set-default CA_MC_R2_PX 0.866025
param set-default CA_MC_R2_PY -0.5
param set-default CA_MC_R2_KM -0.05
param set-default CA_MC_R3_PX -0.866025
param set-default CA_MC_R3_PY 0.5
param set-default CA_MC_R3_KM 0.05
param set-default CA_MC_R4_PX 0.866025
param set-default CA_MC_R4_PY 0.5
param set-default CA_MC_R4_KM 0.05
param set-default CA_MC_R5_PX -0.866025
param set-default CA_MC_R5_PY -0.5
param set-default CA_MC_R5_KM -0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
@@ -19,19 +19,19 @@ param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.177
param set-default CA_ROTOR0_PY 0.177
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.177
param set-default CA_ROTOR1_PY -0.177
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.177
param set-default CA_ROTOR2_PY -0.177
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.177
param set-default CA_ROTOR3_PY 0.177
param set-default CA_ROTOR3_KM -0.05
param set-default CA_MC_R_COUNT 4
param set-default CA_MC_R0_PX 0.177
param set-default CA_MC_R0_PY 0.177
param set-default CA_MC_R0_KM 0.05
param set-default CA_MC_R1_PX -0.177
param set-default CA_MC_R1_PY -0.177
param set-default CA_MC_R1_KM 0.05
param set-default CA_MC_R2_PX 0.177
param set-default CA_MC_R2_PY -0.177
param set-default CA_MC_R2_KM -0.05
param set-default CA_MC_R3_PX -0.177
param set-default CA_MC_R3_PY 0.177
param set-default CA_MC_R3_KM -0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
@@ -15,31 +15,31 @@
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 6
param set-default CA_MC_R_COUNT 6
param set-default CA_ROTOR0_PX 0.0
param set-default CA_ROTOR0_PY 0.275
param set-default CA_ROTOR0_KM -0.05
param set-default CA_MC_R0_PX 0.0
param set-default CA_MC_R0_PY 0.275
param set-default CA_MC_R0_KM -0.05
param set-default CA_ROTOR1_PX 0.0
param set-default CA_ROTOR1_PY -0.275
param set-default CA_ROTOR1_KM 0.05
param set-default CA_MC_R1_PX 0.0
param set-default CA_MC_R1_PY -0.275
param set-default CA_MC_R1_KM 0.05
param set-default CA_ROTOR2_PX 0.238
param set-default CA_ROTOR2_PY -0.1375
param set-default CA_ROTOR2_KM -0.05
param set-default CA_MC_R2_PX 0.238
param set-default CA_MC_R2_PY -0.1375
param set-default CA_MC_R2_KM -0.05
param set-default CA_ROTOR3_PX -0.238
param set-default CA_ROTOR3_PY 0.1375
param set-default CA_ROTOR3_KM 0.05
param set-default CA_MC_R3_PX -0.238
param set-default CA_MC_R3_PY 0.1375
param set-default CA_MC_R3_KM 0.05
param set-default CA_ROTOR4_PX 0.238
param set-default CA_ROTOR4_PY 0.1375
param set-default CA_ROTOR4_KM 0.05
param set-default CA_MC_R4_PX 0.238
param set-default CA_MC_R4_PY 0.1375
param set-default CA_MC_R4_KM 0.05
param set-default CA_ROTOR5_PX -0.238
param set-default CA_ROTOR5_PY -0.1375
param set-default CA_ROTOR5_KM -0.05
param set-default CA_MC_R5_PX -0.238
param set-default CA_MC_R5_PY -0.1375
param set-default CA_MC_R5_KM -0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
@@ -48,14 +48,6 @@ fi
# End Estimator Group Selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start Airship Attitude Controller.
#
-8
View File
@@ -10,14 +10,6 @@
#
ekf2 start &
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start attitude controller.
#
-7
View File
@@ -12,13 +12,6 @@ ekf2 start &
#attitude_estimator_q start
#local_position_estimator start
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start attitude controllers.
+13
View File
@@ -4,6 +4,19 @@
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
if ! ver hwcmp OMNIBUS_F4SD
then
if ! ver hwcmp BITCRAZE_CRAZYFLIE
then
# Configure all I2C buses to 100 KHz as they
# are all external or slow
# TODO: move this
pwm_out i2c 1 100000
pwm_out i2c 2 100000
fi
fi
###############################################################################
# Begin Optional drivers #
###############################################################################
-8
View File
@@ -15,14 +15,6 @@ ekf2 start &
# End Estimator Group Selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
#
# Start UUV Attitude Controller.
#
-8
View File
@@ -15,14 +15,6 @@ ekf2 start &
# End Estimator group selection #
###############################################################################
if param compare SYS_CTRL_ALLOC 1
then
#
# Start Control Allocator
#
control_allocator start
fi
airspeed_selector start
vtol_att_control start
+22 -6
View File
@@ -72,7 +72,28 @@ then
umount /fs/microsd
else
set SDCARD_AVAILABLE yes
# very basic I/O test
set PX4_INIT_TEST_FILE "/fs/microsd/.px4_init_test_file"
date >> $PX4_INIT_TEST_FILE
if [ $? -eq 0 -a -f $PX4_INIT_TEST_FILE ]
then
cat $PX4_INIT_TEST_FILE
rm $PX4_INIT_TEST_FILE
if [ $? -eq 0 -a ! -f $PX4_INIT_TEST_FILE ]
then
set SDCARD_AVAILABLE yes
fi
fi
unset PX4_INIT_TEST_FILE
if [ $SDCARD_AVAILABLE = no ]
then
echo "ERROR [init] card I/O failure, formatting"
set SDCARD_FORMAT yes
umount /fs/microsd
fi
fi
fi
@@ -158,11 +179,6 @@ else
# try importing from backup file
if [ -f "/fs/microsd/parameters_backup.bson" ]
then
echo "[init] importing from parameter backup"
# dump current backup file contents for comparison
param dump /fs/microsd/parameters_backup.bson
param import /fs/microsd/parameters_backup.bson
fi
fi
@@ -33,11 +33,15 @@
px4_add_romfs_files(
autogyro_sitl.main.mix
boat_sitl.main.mix
delta_wing_sitl.main.mix
package_drop.aux.mix
plane_sitl.main.mix
quad_x_vtol.main.mix
rover_ackermann_sitl.main.mix
rover_diff_sitl.main.mix
standard_vtol_sitl.main.mix
tiltrotor_sitl.main.mix
uuv_x_sitl.main.mix
vectored6dof_sitl.main.mix
)
@@ -0,0 +1,15 @@
Mixer for SITL boat
=========================================================
Throttle of left propeller of boat on Output 0
---------------------------------------
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Throttle of right propeller of boat on Output 1
---------------------------------------
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
@@ -0,0 +1,46 @@
Mixer for SITL rover
=========================================================
Output 0
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
Output 1
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
Output 2
---------------------------------------
Z:
Output 3
---------------------------------------
Z:
Output 4
---------------------------------------
Z:
Output 5
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 6
---------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 7
---------------------------------------
Z:
Output 8
---------------------------------------
Z:
@@ -0,0 +1,46 @@
Mixer for SITL rover
=========================================================
Output 0
---------------------------------------
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 1
---------------------------------------
M: 2
S: 0 2 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 2
---------------------------------------
Z:
Output 3
---------------------------------------
Z:
Output 4
---------------------------------------
Z:
Output 5
---------------------------------------
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 6
---------------------------------------
M: 2
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
Output 7
---------------------------------------
Z:
Output 8
---------------------------------------
Z:
@@ -0,0 +1,40 @@
# Motor 1
M: 3
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
S: 0 4 -4000 -4000 0 -4000 +4000
# Motor 2
M: 3
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
S: 0 4 +4000 +4000 0 -4000 +4000
# Motor 3
M: 3
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
S: 0 4 +4000 +4000 0 -4000 +4000
# Motor 4
M: 3
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
S: 0 4 -4000 -4000 0 -4000 +4000
# Motor 5
M: 3
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
S: 0 5 -4000 -4000 0 -4000 +4000
# Motor 6
M: 3
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
S: 0 5 +4000 +4000 0 -4000 +4000
# Motor 7
M: 3
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
S: 0 5 +4000 +4000 0 -4000 +4000
# Motor 8
M: 3
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
S: 0 5 -4000 -4000 0 -4000 +4000
+19 -48
View File
@@ -7,8 +7,6 @@ from argparse import ArgumentParser
import re
import sys
import datetime
import serial.tools.list_ports as list_ports
import tempfile
COLOR_RED = "\x1b[31m"
COLOR_GREEN = "\x1b[32m"
@@ -38,9 +36,8 @@ def print_line(line):
else:
print('{0}'.format(line), end='')
def monitor_firmware_upload(port_url, baudrate):
ser = serial.serial_for_url(url=port_url, baudrate=baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=3, xonxoff=False, rtscts=False, dsrdtr=False, inter_byte_timeout=1)
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()
@@ -52,59 +49,33 @@ def monitor_firmware_upload(port_url, baudrate):
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if "ERROR" in serial_line:
return_code = -1
print_line(serial_line)
if "NuttShell (NSH)" in serial_line:
sys.exit(return_code)
elif "nsh>" in serial_line:
sys.exit(return_code)
if "NuttShell (NSH)" in serial_line:
sys.exit(return_code)
elif "nsh>" in serial_line:
sys.exit(return_code)
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout")
sys.exit(-1)
# newline every 10 seconds if still running
if (len(serial_line) <= 0) and (time.monotonic() - timeout_newline > 10):
timeout_newline = time.monotonic()
ser.write("\n".encode("ascii"))
if time.monotonic() > 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()
ser.write("\n".encode("ascii"))
ser.flush()
def main():
default_device = None
device_required = True
# select USB UART as default if there's only 1
ports = list(serial.tools.list_ports.grep('USB UART'))
if (len(ports) == 1):
default_device = ports[0].device
device_required = False
print("Default USB UART port: {0}".format(ports[0].name))
print(" device: {0}".format(ports[0].device))
print(" description: \"{0}\" ".format(ports[0].description))
print(" hwid: {0}".format(ports[0].hwid))
#print(" vid: {0}, pid: {1}".format(ports[0].vid, ports[0].pid))
#print(" serial_number: {0}".format(ports[0].serial_number))
#print(" location: {0}".format(ports[0].location))
print(" manufacturer: {0}".format(ports[0].manufacturer))
#print(" product: {0}".format(ports[0].product))
#print(" interface: {0}".format(ports[0].interface))
parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=default_device, help='', required=device_required)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="serial port baud rate (default=57600)", default=57600)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
args = parser.parse_args()
tmp_file = "{0}/pyserial_spy_file.txt".format(tempfile.gettempdir())
port_url = "spy://{0}?file={1}".format(args.device, tmp_file)
print("pyserial url: {0}".format(port_url))
monitor_firmware_upload(port_url, args.baudrate)
monitor_firmware_upload(args.device, args.baudrate)
if __name__ == "__main__":
main()
+51 -83
View File
@@ -6,9 +6,6 @@ from subprocess import call, Popen
from argparse import ArgumentParser
import re
import sys
import datetime
import serial.tools.list_ports as list_ports
import tempfile
COLOR_RED = "\x1b[31m"
COLOR_GREEN = "\x1b[32m"
@@ -32,38 +29,33 @@ def print_line(line):
if "FAILED" in line:
line = line.replace("FAILED", f"{COLOR_RED}FAILED{COLOR_RESET}", 1)
if "\n" in line:
current_time = datetime.datetime.now()
print('[{0}] {1}'.format(current_time.isoformat(timespec='milliseconds'), line), end='')
else:
print('{0}'.format(line), end='')
print(line, end='')
def do_param_set_cmd(port_url, baudrate, param_name, param_value):
ser = serial.serial_for_url(url=port_url, baudrate=baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=3, xonxoff=False, rtscts=False, dsrdtr=False, inter_byte_timeout=1)
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 = 30 # 30 seconds
ser.write("\n\n\n".encode("ascii"))
# wait for nsh prompt
while True:
ser.write("\n".encode("ascii"))
ser.flush()
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if "nsh>" in serial_line:
break
if "nsh>" in serial_line:
break
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
sys.exit(1)
ser.write("\n".encode("ascii"))
if len(serial_line) > 0:
print_line(serial_line)
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
sys.exit(1)
# clear
ser.reset_input_buffer()
ser.readlines()
# run command
timeout_start = time.monotonic()
@@ -73,32 +65,28 @@ def do_param_set_cmd(port_url, baudrate, param_name, param_value):
# write command (param set) and wait for command echo
print("Running command: \'{0}\'".format(cmd))
serial_cmd = '{0}\n'.format(cmd)
serial_cmd = '{0}\r\n'.format(cmd)
ser.write(serial_cmd.encode("ascii"))
ser.flush()
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if cmd in serial_line:
break
if cmd in serial_line:
print_line(serial_line)
break
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
if len(serial_line) > 0:
print_line(serial_line)
# clear
ser.reset_input_buffer()
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
# verify param value
cmd = "param show " + param_name
print("Running command: \'{0}\'".format(cmd))
serial_cmd = '{0}\n'.format(cmd)
serial_cmd = '{0}\r\n'.format(cmd)
ser.write(serial_cmd.encode("ascii"))
ser.flush()
param_show_response = param_name + " ["
@@ -108,64 +96,44 @@ def do_param_set_cmd(port_url, baudrate, param_name, param_value):
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if param_show_response in serial_line:
print_line(serial_line)
current_param_value = serial_line.split(":")[-1].strip()
if param_show_response in serial_line:
current_param_value = serial_line.split(":")[-1].strip()
if (current_param_value == param_value):
sys.exit(0)
else:
sys.exit(1)
if (current_param_value == param_value):
sys.exit(0)
else:
if time.monotonic() > 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
sys.exit(1)
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout")
sys.exit(-1)
if len(serial_line) > 0:
print_line(serial_line)
if time.monotonic() > 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)
ser.close()
def main():
default_device = None
device_required = True
# select USB UART as default if there's only 1
ports = list(serial.tools.list_ports.grep('USB UART'))
if (len(ports) == 1):
default_device = ports[0].device
device_required = False
print("Default USB UART port: {0}".format(ports[0].name))
print(" device: {0}".format(ports[0].device))
print(" description: \"{0}\" ".format(ports[0].description))
print(" hwid: {0}".format(ports[0].hwid))
#print(" vid: {0}, pid: {1}".format(ports[0].vid, ports[0].pid))
#print(" serial_number: {0}".format(ports[0].serial_number))
#print(" location: {0}".format(ports[0].location))
print(" manufacturer: {0}".format(ports[0].manufacturer))
#print(" product: {0}".format(ports[0].product))
#print(" interface: {0}".format(ports[0].interface))
parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=default_device, help='', required=device_required)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="serial port baud rate (default=57600)", default=57600)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
parser.add_argument("--name", "-p", dest="param_name", help="Parameter name")
parser.add_argument("--value", "-v", dest="param_value", help="Parameter value")
args = parser.parse_args()
tmp_file = "{0}/pyserial_spy_file.txt".format(tempfile.gettempdir())
port_url = "spy://{0}?file={1}".format(args.device, tmp_file)
print("pyserial url: {0}".format(port_url))
do_param_set_cmd(port_url, args.baudrate, args.param_name, args.param_value)
do_param_set_cmd(args.device, args.baudrate, args.param_name, args.param_value)
if __name__ == "__main__":
main()
+20 -44
View File
@@ -7,8 +7,6 @@ from argparse import ArgumentParser
import re
import sys
import datetime
import serial.tools.list_ports as list_ports
import tempfile
COLOR_RED = "\x1b[31m"
COLOR_GREEN = "\x1b[32m"
@@ -38,15 +36,15 @@ def print_line(line):
else:
print('{0}'.format(line), end='')
def reboot(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)
def reboot(port_url, baudrate):
ser = serial.serial_for_url(url=port_url, baudrate=baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=3, xonxoff=False, rtscts=False, dsrdtr=False, inter_byte_timeout=1)
# clear
ser.readlines()
time_start = time.monotonic()
ser.write("\n\n\n".encode("ascii"))
ser.write("reboot\n".encode("ascii"))
ser.write("\nreboot\n".encode("ascii"))
ser.flush()
time_reboot_cmd = time_start
timeout_reboot_cmd = 90
@@ -55,53 +53,31 @@ def reboot(port_url, baudrate):
return_code = 0
while True:
if time.monotonic() > time_reboot_cmd + timeout_reboot_cmd:
time_reboot_cmd = time.monotonic()
print("sending reboot cmd again")
ser.write("reboot\n".encode("ascii"))
ser.flush()
time.sleep(0.2)
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
print_line(serial_line)
if "ERROR" in serial_line:
return_code = -1
if "NuttShell (NSH)" in serial_line:
sys.exit(return_code)
print_line(serial_line)
else:
if time.monotonic() > time_start + timeout:
print("Error, timeout")
sys.exit(-1)
if time.monotonic() > time_reboot_cmd + timeout_reboot_cmd:
time_reboot_cmd = time.monotonic()
print("sending reboot cmd again")
ser.write("reboot\n".encode("ascii"))
if "NuttShell (NSH)" in serial_line:
sys.exit(return_code)
if time.monotonic() > time_start + timeout:
print("Error, timeout")
sys.exit(-1)
def main():
default_device = None
device_required = True
# select USB UART as default if there's only 1
ports = list(serial.tools.list_ports.grep('USB UART'))
if (len(ports) == 1):
default_device = ports[0].device
device_required = False
print("Default USB UART port: {0}".format(ports[0].name))
print(" device: {0}".format(ports[0].device))
print(" description: \"{0}\" ".format(ports[0].description))
print(" hwid: {0}".format(ports[0].hwid))
#print(" vid: {0}, pid: {1}".format(ports[0].vid, ports[0].pid))
#print(" serial_number: {0}".format(ports[0].serial_number))
#print(" location: {0}".format(ports[0].location))
print(" manufacturer: {0}".format(ports[0].manufacturer))
#print(" product: {0}".format(ports[0].product))
#print(" interface: {0}".format(ports[0].interface))
parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=default_device, help='', required=device_required)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
args = parser.parse_args()
+50 -72
View File
@@ -7,8 +7,6 @@ from argparse import ArgumentParser
import re
import sys
import datetime
import serial.tools.list_ports as list_ports
import tempfile
COLOR_RED = "\x1b[31m"
COLOR_GREEN = "\x1b[32m"
@@ -39,59 +37,59 @@ def print_line(line):
print('{0}'.format(line), end='')
def do_nsh_cmd(port_url, baudrate, cmd):
ser = serial.serial_for_url(url=port_url, baudrate=baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=False, rtscts=False, dsrdtr=False, inter_byte_timeout=1)
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 = 30 # 30 seconds
ser.write("\n\n\n".encode("ascii"))
# wait for nsh prompt
while True:
ser.write("\n".encode("ascii"))
ser.flush()
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if "nsh>" in serial_line:
break
if "nsh>" in serial_line:
break
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
sys.exit(1)
ser.write("\n".encode("ascii"))
if len(serial_line) > 0:
print_line(serial_line)
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
sys.exit(1)
# clear
ser.reset_input_buffer()
ser.readlines()
# run command
timeout_start = time.monotonic()
timeout = 5 # 5 seconds
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}";\n'.format(cmd, success_cmd, success_cmd)
serial_cmd = '{0}; echo "{1}"; echo "{2}";\r\n'.format(cmd, success_cmd, success_cmd)
ser.write(serial_cmd.encode("ascii"))
ser.flush()
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if cmd in serial_line:
break
elif serial_line.startswith(success_cmd) and len(serial_line) <= len(success_cmd) + 2:
print_line(serial_line)
# we missed the echo, but command ran and succeeded
sys.exit(0)
else:
print_line(serial_line)
if cmd in serial_line:
break
elif serial_line.startswith(success_cmd) and len(serial_line) <= len(success_cmd) + 2:
print_line(serial_line)
# we missed the echo, but command ran and succeeded
sys.exit(0)
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
if len(serial_line) > 0:
print_line(serial_line)
if (len(serial_line) <= 0) and (time.monotonic() > timeout_start + timeout):
print("Error, timeout waiting for command echo")
break
timeout_start = time.monotonic()
@@ -102,60 +100,40 @@ def do_nsh_cmd(port_url, baudrate, cmd):
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if success_cmd in serial_line:
sys.exit(return_code)
else:
if success_cmd in serial_line:
sys.exit(return_code)
break
else:
if len(serial_line) > 0:
if "ERROR " in serial_line:
return_code = -1
print_line(serial_line)
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
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout")
sys.exit(-1)
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 (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)
ser.close()
def main():
default_device = None
device_required = True
# select USB UART as default if there's only 1
ports = list(serial.tools.list_ports.grep('USB UART'))
if (len(ports) == 1):
default_device = ports[0].device
device_required = False
print("Default USB UART port: {0}".format(ports[0].name))
print(" device: {0}".format(ports[0].device))
print(" description: \"{0}\" ".format(ports[0].description))
print(" hwid: {0}".format(ports[0].hwid))
#print(" vid: {0}, pid: {1}".format(ports[0].vid, ports[0].pid))
#print(" serial_number: {0}".format(ports[0].serial_number))
#print(" location: {0}".format(ports[0].location))
print(" manufacturer: {0}".format(ports[0].manufacturer))
#print(" product: {0}".format(ports[0].product))
#print(" interface: {0}".format(ports[0].interface))
parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=default_device, help='', required=device_required)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="serial port baud rate (default=57600)", default=57600)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
parser.add_argument("--cmd", "-c", dest="cmd", help="Command to run")
args = parser.parse_args()
tmp_file = "{0}/pyserial_spy_file.txt".format(tempfile.gettempdir())
port_url = "spy://{0}?file={1}".format(args.device, tmp_file)
print("pyserial url: {0}".format(port_url))
do_nsh_cmd(port_url, args.baudrate, args.cmd)
do_nsh_cmd(args.device, args.baudrate, args.cmd)
if __name__ == "__main__":
main()
+46 -75
View File
@@ -9,9 +9,6 @@ import unittest
import os
import sys
import datetime
import serial.tools.list_ports as list_ports
import tempfile
import warnings
COLOR_RED = "\x1b[31m"
COLOR_GREEN = "\x1b[32m"
@@ -41,36 +38,33 @@ def print_line(line):
else:
print('{0}'.format(line), end='')
def do_test(port_url, baudrate, test_name):
# ignore pyserial spy:// resource warnings
warnings.filterwarnings(action="ignore", message="unclosed", category=ResourceWarning)
ser = serial.serial_for_url(url=port_url, baudrate=baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=3, xonxoff=False, rtscts=False, dsrdtr=False, inter_byte_timeout=1)
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 = 30 # 30 seconds
ser.write("\n\n\n".encode("ascii"))
# wait for nsh prompt
while True:
ser.write("\n".encode("ascii"))
ser.flush()
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if "nsh>" in serial_line:
break
if "nsh>" in serial_line:
break
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
return False
ser.write("\n".encode("ascii"))
if len(serial_line) > 0:
print(serial_line, end='')
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
return False
# clear
ser.reset_input_buffer()
ser.readlines()
success = False
# run test cmd
print('\n|======================================================================')
@@ -85,17 +79,20 @@ def do_test(port_url, baudrate, test_name):
print("Running command: \'{0}\'".format(cmd))
serial_cmd = '{0}\n'.format(cmd)
ser.write(serial_cmd.encode("ascii"))
ser.flush()
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
if len(serial_line) > 0:
if cmd in serial_line:
break
if cmd in serial_line:
break
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
if len(serial_line) > 0:
print_line(serial_line)
if time.monotonic() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
# print results, wait for final result (PASSED or FAILED)
timeout = 300 # 5 minutes
@@ -108,26 +105,27 @@ def do_test(port_url, baudrate, test_name):
if len(serial_line) > 0:
print_line(serial_line)
if test_name + " PASSED" in serial_line:
ser.close()
return True
elif test_name + " FAILED" in serial_line:
ser.close()
return False
else:
if time.monotonic() > timeout_start + timeout:
print("Error, timeout")
print(test_name + f" {COLOR_RED}FAILED{COLOR_RESET}")
ser.close()
return False
if test_name + " PASSED" in serial_line:
success = True
break
elif test_name + " FAILED" in serial_line:
success = False
break
# newline every 30 seconds if still running
if time.monotonic() - timeout_newline > 30:
ser.write("\n".encode("ascii"))
timeout_newline = time.monotonic()
if time.monotonic() > 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):
ser.write("\n".encode("ascii"))
timeout_newline = time.monotonic()
ser.close()
return False
return success
class TestHardwareMethods(unittest.TestCase):
TEST_DEVICE = 0
@@ -209,39 +207,12 @@ class TestHardwareMethods(unittest.TestCase):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "versioning"))
def main():
default_device = None
device_required = True
# select USB UART as default if there's only 1
ports = list(serial.tools.list_ports.grep('USB UART'))
if (len(ports) == 1):
default_device = ports[0].device
device_required = False
print("Default USB UART port: {0}".format(ports[0].name))
print(" device: {0}".format(ports[0].device))
print(" description: \"{0}\" ".format(ports[0].description))
print(" hwid: {0}".format(ports[0].hwid))
#print(" vid: {0}, pid: {1}".format(ports[0].vid, ports[0].pid))
#print(" serial_number: {0}".format(ports[0].serial_number))
#print(" location: {0}".format(ports[0].location))
print(" manufacturer: {0}".format(ports[0].manufacturer))
#print(" product: {0}".format(ports[0].product))
#print(" interface: {0}".format(ports[0].interface))
parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=default_device, help='', required=device_required)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="serial port baud rate (default=57600)", default=57600)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)
parser.add_argument("--baudrate", "-b", dest="baudrate", type=int, help="Mavlink port baud rate (default=57600)", default=57600)
args = parser.parse_args()
tmp_file = "{0}/pyserial_spy_file.txt".format(tempfile.gettempdir())
port_url = "spy://{0}?file={1}".format(args.device, tmp_file)
print("pyserial url: {0}".format(port_url))
TestHardwareMethods.TEST_DEVICE = port_url
TestHardwareMethods.TEST_DEVICE = args.device
TestHardwareMethods.TEST_BAUDRATE = args.baudrate
unittest.main(__name__, failfast=True, verbosity=0, argv=['main'])
-6
View File
@@ -29,16 +29,10 @@ do
${DIR}/nsh_param_set.py --device ${SERIAL_DEVICE} --name SYS_AUTOSTART --value $airframe
${DIR}/nsh_param_set.py --device ${SERIAL_DEVICE} --name CBRK_BUZZER --value 782097
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param reset SYS_HITL'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param status'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param save'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump'
${DIR}/reboot.py --device ${SERIAL_DEVICE}
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump /fs/mtd_params' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump /fs/microsd/parameters_backup.bson' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump /fs/microsd/param_import_fail.bson' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'ps'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'work_queue status'
+1 -1
View File
@@ -19,7 +19,7 @@ if [ -z ${PX4_DOCKER_REPO+x} ]; then
PX4_DOCKER_REPO="px4io/px4-dev-clang:2021-02-04"
elif [[ $@ =~ .*tests* ]]; then
# run all tests with simulation
PX4_DOCKER_REPO="px4io/px4-dev-simulation-bionic:2021-12-11"
PX4_DOCKER_REPO="px4io/px4-dev-simulation-bionic:2021-02-04"
fi
else
echo "PX4_DOCKER_REPO is set to '$PX4_DOCKER_REPO'";
@@ -130,8 +130,7 @@ def get_actuator_output(yaml_config, output_functions, timer_config_file, verbos
return None
actuator_output_yaml = yaml_config['actuator_output']
output_groups = actuator_output_yaml['output_groups']
output_groups = yaml_config['actuator_output']['output_groups']
module_name = process_module_name(yaml_config['module_name'])
group_idx = 0
@@ -140,9 +139,8 @@ def get_actuator_output(yaml_config, output_functions, timer_config_file, verbos
actuator_output = {
'label': module_name
}
if 'show_subgroups_if' in actuator_output_yaml:
actuator_output['show-subgroups-if'] = actuator_output_yaml['show_subgroups_if']
add_reverse_range_param = actuator_output_yaml.get('add_reverse_range_param', False)
if 'show_subgroups_if' in yaml_config['actuator_output']:
actuator_output['show-subgroups-if'] = yaml_config['actuator_output']['show_subgroups_if']
# config parameters
def get_config_params(param_list):
@@ -161,7 +159,7 @@ def get_actuator_output(yaml_config, output_functions, timer_config_file, verbos
parameters.append(param)
return parameters
parameters = get_config_params(actuator_output_yaml.get('config_parameters', []))
parameters = get_config_params(yaml_config['actuator_output'].get('config_parameters', []))
if len(parameters) > 0:
actuator_output['parameters'] = parameters
@@ -256,16 +254,6 @@ def get_actuator_output(yaml_config, output_functions, timer_config_file, verbos
if show_if: param['show-if'] = show_if
per_channel_params.append(param)
if add_reverse_range_param:
param = {
'label': 'Rev Range\n(for Servos)',
'name': param_prefix+'_REV',
'index-offset': -1,
'show-as': 'bitset',
}
per_channel_params.append(param)
# TODO: support non-standard per-channel parameters
subgroup['per-channel-parameters'] = per_channel_params
@@ -358,39 +346,33 @@ def get_mixers(yaml_config, output_functions, verbose):
if 'count' in actuator_conf: # possibly dynamic size
actuator['count'] = actuator_conf['count']
per_item_params = actuator_conf.get('per_item_parameters', {})
per_item_params = actuator_conf['per_item_parameters']
params = []
if 'standard' in per_item_params:
standard_params = per_item_params['standard']
index_offset = standard_params.get('index_offset', 0)
if 'position' in standard_params:
params.extend([
{
'label': 'Position X',
'function': 'posx',
'name': standard_params['position'][0],
'index-offset': index_offset,
},
{
'label': 'Position Y',
'function': 'posy',
'name': standard_params['position'][1],
'index-offset': index_offset,
},
{
'label': 'Position Z',
'function': 'posz',
'name': standard_params['position'][2],
'advanced': True,
'index-offset': index_offset,
},
])
if 'extra' in per_item_params:
for extra_param in per_item_params['extra']:
params.append({k.replace('_','-'): v for k, v in extra_param.items()})
actuator['per-item-parameters'] = params
if 'item_label_prefix' in actuator_conf:
actuator['item-label-prefix'] = actuator_conf['item_label_prefix']
else: # fixed size
labels = []
pos_x = []
@@ -435,18 +417,10 @@ def get_mixers(yaml_config, output_functions, verbose):
if verbose:
print('Mixer configs: {}'.format(config))
rules = []
for rule in yaml_config['mixer'].get('rules', []):
rules.append({k.replace('_','-'): v for k, v in rule.items()})
if verbose:
print('Mixer rules: {}'.format(rules))
mixers = {
'actuator-types': actuator_types,
'config': config,
'rules': rules,
}
return mixers
+2 -44
View File
@@ -110,15 +110,8 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
param_type = 'INT32'
for key in param['values']:
tags += '\n * @value {:} {:}'.format(key, param['values'][key])
elif param['type'] == 'bitmask':
param_type = 'INT32'
for key in param['bit']:
tags += '\n * @bit {:} {:}'.format(key, param['bit'][key])
max_val = max(key for key in param['bit'])
tags += '\n * @min 0'
tags += '\n * @max {:}'.format((1<<(max_val+1)) - 1)
elif param['type'] == 'boolean':
param_type = 'INT32'
param_type = 'BOOL'
tags += '\n * @boolean'
elif param['type'] == 'int32':
param_type = 'INT32'
@@ -127,7 +120,7 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
else:
raise Exception("unknown param type {:}".format(param['type']))
for tag in ['decimal', 'increment', 'category', 'volatile',
for tag in ['decimal', 'increment', 'category', 'volatile', 'bit',
'min', 'max', 'unit', 'reboot_required']:
if tag in param:
tags += '\n * @{:} {:}'.format(tag, param[tag])
@@ -143,9 +136,6 @@ 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 += '''
/**
@@ -178,9 +168,6 @@ def get_actuator_output_params(yaml_config, output_functions,
all_params = {}
group_idx = 0
add_reverse_range_param = yaml_config['actuator_output'].get('add_reverse_range_param', False)
all_param_prefixes = {}
def add_local_param(param_name, param_def):
nonlocal all_params
# add as a list, as there can be multiple entries with the same param_name
@@ -262,11 +249,6 @@ def get_actuator_output_params(yaml_config, output_functions,
for i in range(count):
output_function_values[start+i] = function_name_label+' '+str(i+1)
if param_prefix not in all_param_prefixes:
all_param_prefixes[param_prefix] = []
all_param_prefixes[param_prefix].append((instance_start,
instance_start_label, num_channels, channel_label))
# function param
param = {
'description': {
@@ -346,30 +328,6 @@ When set to -1 (default), the value depends on the function (see {:}).
}
add_local_param(param_prefix+'_'+param_suffix+'${i}', param)
if add_reverse_range_param:
for param_prefix in all_param_prefixes:
groups = all_param_prefixes[param_prefix]
# collect the bits
channel_bits = {}
for instance_start, instance_start_label, num_instances, label in groups:
for instance in range(instance_start, instance_start+num_instances):
instance_label = instance - instance_start + instance_start_label
channel_bits[instance-1] = label + ' ' + str(instance_label)
param = {
'description': {
'short': 'Reverse Output Range for '+module_name,
'long':
'''Allows to reverse the output range for each channel.
Note: this is only useful for servos.
'''.format(channel_label),
},
'type': 'bitmask',
'default': 0,
'bit': channel_bits
}
add_local_param(param_prefix+'_REV', param)
if verbose: print('adding actuator params: {:}'.format(all_params))
return all_params
+27 -13
View File
@@ -72,27 +72,38 @@ div.frame_variant td, div.frame_variant th {
# check if all outputs are equal for the group: if so, show them
# only once
all_outputs = {}
num_configs = len(group.GetParams())
outputs_prev = ['', ''] # split into MAINx and others (AUXx)
outputs_match = [True, True]
for param in group.GetParams():
if not self.IsExcluded(param, board):
outputs_current = ['', '']
for output_name in param.GetOutputCodes():
value = param.GetOutputValue(output_name)
key_value_pair = (output_name, value)
if key_value_pair not in all_outputs:
all_outputs[key_value_pair] = 0
all_outputs[key_value_pair] += 1
has_common_outputs = any(all_outputs[k] == num_configs for k in all_outputs)
if output_name.lower().startswith('main'):
idx = 0
else:
idx = 1
outputs_current[idx] += '<li><b>%s</b>: %s</li>' % (output_name, value)
for i in range(2):
if len(outputs_current[i]) != 0:
if outputs_prev[i] == '':
outputs_prev[i] = outputs_current[i]
elif outputs_current[i] != outputs_prev[i]:
outputs_match[i] = False
if has_common_outputs:
outputs_common = ''.join(['<li><b>{:}</b>: {:}</li>'.format(k[0], k[1]) \
for k in all_outputs if all_outputs[k] == num_configs])
for i in range(2):
if len(outputs_prev[i]) == 0:
outputs_match[i] = False
if not outputs_match[i]:
outputs_prev[i] = ''
if outputs_match[0] or outputs_match[1]:
result += '<table>\n'
result += ' <thead>\n'
result += ' <tr><th>Common Outputs</th></tr>\n'
result += ' </thead>\n'
result += ' <tbody>\n'
result += '<tr>\n <td><ul>%s</ul></td>\n</tr>\n' % (outputs_common)
result += '<tr>\n <td><ul>%s%s</ul></td>\n</tr>\n' % (outputs_prev[0], outputs_prev[1])
result += '</tbody></table>\n'
result += '</div>\n\n'
@@ -127,8 +138,11 @@ div.frame_variant td, div.frame_variant th {
for output_name in param.GetOutputCodes():
value = param.GetOutputValue(output_name)
valstrs = value.split(";")
key_value_pair = (output_name, value)
if all_outputs[key_value_pair] < num_configs:
if output_name.lower().startswith('main'):
idx = 0
else:
idx = 1
if not outputs_match[idx]:
outputs += '<li><b>%s</b>: %s</li>' % (output_name, value)
has_outputs = True
@@ -35,6 +35,8 @@ CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
@@ -46,5 +48,6 @@ CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
@@ -19,6 +19,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -33,17 +34,21 @@ CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
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_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
+1 -1
View File
@@ -5,7 +5,7 @@
board_adc start
# SPI1
if ! icm20689 -s -b 1 -R 2 -q start
if ! icm20689 -s -b 1 -R 2 start
then
adis16470 -s -b 1 -R 2 start
fi
+5 -1
View File
@@ -9,8 +9,10 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP280=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
@@ -19,10 +21,10 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -31,9 +33,11 @@ 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=n
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_PARAM=y
+2 -2
View File
@@ -39,7 +39,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
@@ -63,6 +62,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
@@ -73,8 +73,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_ESC_CALIB=y
@@ -6,4 +6,5 @@
param set-default BAT1_V_DIV 10.1
param set-default BAT1_A_PER_V 24
safety_button start
@@ -30,7 +30,7 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1024
CONFIG_CDCACM_PRODUCTID=0x1023
CONFIG_CDCACM_PRODUCTSTR="PX4 BL mRo ControlZeroH7 OEM"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
@@ -222,35 +222,34 @@
/* UART/USART */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
#define GPIO_USART6_TX 0 /* USART6 is RX-only */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
/* SPI */
@@ -199,6 +199,7 @@ SECTIONS
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
.sram4_reserve (NOLOAD) :
{
*(.sram4)
@@ -77,6 +77,7 @@
/* CAN Silence: Silent mode control */
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
#define GPIO_CAN2_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS 8
@@ -168,6 +169,7 @@
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_CAN2_SILENT_S0, \
GPIO_nPOWER_IN_A, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_TONE_ALARM_IDLE, \
+2 -2
View File
@@ -40,7 +40,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
@@ -64,6 +63,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
@@ -74,8 +74,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_ESC_CALIB=y
@@ -221,32 +221,32 @@
/* UART/USART */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
#define GPIO_USART6_TX 0 /* USART6 is RX-only */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
/* SPI */
@@ -262,7 +262,7 @@
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF9 */
/* I2C */
+9
View File
@@ -29,6 +29,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
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_NAVIGATOR=y
@@ -37,5 +38,13 @@ CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
+5
View File
@@ -1,4 +1,7 @@
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL_L1=n
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
@@ -8,7 +11,9 @@ CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
-2
View File
@@ -1,7 +1,5 @@
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525=n
CONFIG_DRIVERS_GPS=n
CONFIG_DRIVERS_IMU_L3GD20=n
CONFIG_DRIVERS_IMU_LSM303D=n
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_EKF2=n
CONFIG_MODULES_FW_ATT_CONTROL=n
+9 -1
View File
@@ -5,11 +5,19 @@
board_adc start
# We know there are sketchy boards out there
# as chinese companies produce Pixracers without
# fully understanding the critical parts of the
# schematic and BOM, leading to sensor brownouts
# on boot. Original Pixracers following the
# open hardware design do not require this.
pwm_out sensor_reset 50
# Internal SPI
ms5611 -s start
# hmc5883 internal SPI bus is rotated 90 deg yaw
if ! hmc5883 -T -s -R 2 -q start
if ! hmc5883 -T -s -R 2 start
then
# lis3mdl internal SPI bus is rotated 90 deg yaw
lis3mdl -s start
+1 -1
View File
@@ -4,7 +4,7 @@
#------------------------------------------------------------------------------
rgbled start -I
rgbled_ncp5623c start -I -q
rgbled_ncp5623c start -I
board_adc start
@@ -38,6 +38,7 @@ CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_STACKCHECK=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
+1 -1
View File
@@ -4,8 +4,8 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IMU_BOSCH_BMI055=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_OSD=n
+1 -1
View File
@@ -3,7 +3,7 @@
# board specific MAVLink startup script.
#------------------------------------------------------------------------------
if ver hwtypecmp V5X90 V5X91 V5Xa0 V5Xa1 V5X80 V5X81
if ver hwtypecmp V5Xa0 V5X91 V5Xa1
then
# Start MAVLink on the UART connected to the mission computer
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
+3
View File
@@ -7,6 +7,9 @@
# IFO
if param compare SYS_AUTOSTART 4071
then
# Change rate to 400 Khz for fast barometer
#pwm_out i2c 1 400000
# IFO has only external i2c barometer.
# It does not start EKF2 in the beginning which is strange behaviour. but 3 seconds hack.
# We intentionally put this initialization to here for delayed initialization.
-2
View File
@@ -44,7 +44,6 @@ set(msg_files
actuator_motors.msg
actuator_outputs.msg
actuator_servos.msg
actuator_servos_trim.msg
actuator_test.msg
adc_report.msg
airspeed.msg
@@ -145,7 +144,6 @@ set(msg_files
sensor_gyro.msg
sensor_gyro_fft.msg
sensor_gyro_fifo.msg
sensor_hygrometer.msg
sensor_mag.msg
sensor_preflight_mag.msg
sensor_selection.msg
-2
View File
@@ -2,8 +2,6 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
uint16 reversible_flags # bitset which motors are configured to be reversible
uint8 NUM_CONTROLS = 8
float32[8] control # range: [-1, 1], where 1 means maximum positive thrust,
# -1 maximum negative (if not supported by the output, <0 maps to NaN),
-5
View File
@@ -1,5 +0,0 @@
# Servo trims, added as offset to servo outputs
uint64 timestamp # time since system start (microseconds)
uint8 NUM_CONTROLS = 8
float32[8] trim # range: [-1, 1]
-1
View File
@@ -7,7 +7,6 @@ uint8 GF_ACTION_TERMINATE = 4 # flight termination
uint8 GF_ACTION_LAND = 5 # switch to AUTO|LAND
bool geofence_violated # true if the geofence is violated
bool geofence_too_close_on_ground # true if vehicle close than GF_MINDIST_GND while landed or disarmed
uint8 geofence_action # action to take when geofence is violated
bool home_required # true if the geofence requires a valid home position
-8
View File
@@ -1,8 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 temperature # Temperature provided by sensor (Celcius)
float32 humidity # Humidity provided by sensor
-1
View File
@@ -88,7 +88,6 @@ bool high_latency_data_link_lost # Set to true if the high latency data link
bool engine_failure # Set to true if an engine failure is detected
bool mission_failure # Set to true if mission could not continue/finish
bool geofence_violated
bool geofence_too_close_on_ground # the vehicle is too close to a geofence boundary while being on the ground
uint8 failure_detector_status # Bitmask containing FailureDetector status [0, 0, 0, 0, 0, FAILURE_ALT, FAILURE_PITCH, FAILURE_ROLL]
+1 -8
View File
@@ -696,14 +696,7 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
}
if (!started && !cli.quiet_start) {
static constexpr char no_instance_started[] {"no instance started (no device on bus?)"};
if (iterator.external()) {
PX4_WARN("%s: %s", px4_get_taskname(), no_instance_started);
} else {
PX4_ERR("%s: %s", px4_get_taskname(), no_instance_started);
}
PX4_WARN("%s: no instance started (no device on bus?)", px4_get_taskname());
#if defined(CONFIG_I2C)
@@ -80,14 +80,6 @@ public:
}
}
void reset()
{
// set bits to false
for (auto &d : _data) {
d.store(0);
}
}
private:
static constexpr uint8_t BITS_PER_ELEMENT = 32;
static constexpr size_t ARRAY_SIZE = ((N % BITS_PER_ELEMENT) == 0) ? (N / BITS_PER_ELEMENT) :
@@ -261,7 +261,7 @@ private:
int32_t _val;
};
//external version
// external version
template<px4::params p>
class Param<int32_t &, p>
{
@@ -318,7 +318,7 @@ class Param<bool, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_BOOL, "parameter type must be bool");
Param()
{
@@ -331,18 +331,10 @@ public:
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
int32_t value_int = (int32_t)_val;
return param_set(handle(), &value_int) == 0;
}
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
int32_t value_int = (int32_t)_val;
return param_set_no_notification(handle(), &value_int) == 0;
}
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
@@ -364,38 +356,83 @@ public:
update();
}
bool update()
{
int32_t value_int;
int ret = param_get(handle(), &value_int);
if (ret == 0) {
_val = value_int != 0;
return true;
}
return false;
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
private:
bool _val;
};
// external version
template<px4::params p>
class Param<bool &, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_BOOL, "parameter type must be bool");
Param(bool &external_val)
: _val(external_val)
{
param_set_used(handle());
update();
}
bool get() const { return _val; }
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(bool val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
private:
bool &_val;
};
template <px4::params p>
using ParamFloat = Param<float, p>;
using ParamBool = Param<bool, p>;
template <px4::params p>
using ParamInt = Param<int32_t, p>;
template <px4::params p>
using ParamExtFloat = Param<float &, p>;
using ParamFloat = Param<float, p>;
template <px4::params p>
using ParamExtBool = Param<bool &, p>;
template <px4::params p>
using ParamExtInt = Param<int32_t &, p>;
template <px4::params p>
using ParamBool = Param<bool, p>;
using ParamExtFloat = Param<float &, p>;
} /* namespace do_not_explicitly_use_this_namespace */
@@ -48,7 +48,7 @@ struct wq_config_t {
namespace wq_configurations
{
static constexpr wq_config_t rate_ctrl{"wq:rate_ctrl", 3150, 0}; // PX4 inner loop highest priority
static constexpr wq_config_t rate_ctrl{"wq:rate_ctrl", 3000, 0}; // PX4 inner loop highest priority
static constexpr wq_config_t SPI0{"wq:SPI0", 2336, -1};
static constexpr wq_config_t SPI1{"wq:SPI1", 2336, -2};
@@ -38,9 +38,7 @@ namespace px4
ScheduledWorkItem::~ScheduledWorkItem()
{
if (_call.arg != nullptr) {
ScheduleClear();
}
ScheduleClear();
}
void ScheduledWorkItem::schedule_trampoline(void *arg)
+2 -2
View File
@@ -103,7 +103,7 @@ file(RELATIVE_PATH PX4_BINARY_DIR_REL ${CMAKE_CURRENT_BINARY_DIR} ${PX4_BINARY_D
# only in the cygwin environment: convert absolute linker script path to mixed windows (C:/...)
# because even relative linker script paths are different for linux, mac and windows
CYGPATH(NUTTX_CONFIG_DIR NUTTX_CONFIG_DIR_CYG)
CYGPATH(PX4_BINARY_DIR PX4_BINARY_DIR_CYG)
target_link_libraries(nuttx_arch
INTERFACE
@@ -125,7 +125,7 @@ target_link_libraries(px4 PRIVATE
-fno-exceptions
-fno-rtti
-Wl,--script=${NUTTX_CONFIG_DIR_CYG}/scripts/${SCRIPT_PREFIX}script.ld
-Wl,--script=${NUTTX_CONFIG_DIR}/scripts/${SCRIPT_PREFIX}script.ld
-Wl,-Map=${PX4_CONFIG}.map
-Wl,--warn-common
-Wl,--gc-sections
+1 -1
View File
@@ -82,7 +82,7 @@ function(px4_os_add_flags)
-ffixed-r10
-finstrument-functions
# instrumenting PX4 Matrix and Param methods is too burdensome
-finstrument-functions-exclude-file-list=matrix/Matrix.hpp,px4_platform_common/param.h,modules__ekf2_unity.cpp
-finstrument-functions-exclude-file-list=matrix/Matrix.hpp,px4_platform_common/param.h
)
endif()
+1 -1
View File
@@ -39,7 +39,7 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_BATT, 0);
PARAM_DEFINE_BOOL(SENS_EN_BATT, 0);
/**
* Capacity/current multiplier for high-current capable SMBUS battery
@@ -70,13 +70,13 @@ CameraCapture::CameraCapture() :
// get the capture channel from function configuration params
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
int32_t ctrl_alloc = 0;
bool ctrl_alloc = false;
if (p_ctrl_alloc != PARAM_INVALID) {
param_get(p_ctrl_alloc, &ctrl_alloc);
}
if (ctrl_alloc == 1) {
if (ctrl_alloc) {
_capture_channel = -1;
for (unsigned i = 0; i < 16 && _capture_channel == -1; ++i) {
@@ -59,7 +59,7 @@ PARAM_DEFINE_FLOAT(CAM_CAP_DELAY, 0.0f);
* @group Camera Control
* @reboot_required true
*/
PARAM_DEFINE_INT32(CAM_CAP_FBACK, 0);
PARAM_DEFINE_BOOL(CAM_CAP_FBACK, 0);
/**
* Camera capture timestamping mode
@@ -84,4 +84,4 @@ PARAM_DEFINE_INT32(CAM_CAP_MODE, 0);
* @group Camera Control
* @reboot_required true
*/
PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0);
PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0);
@@ -43,14 +43,13 @@ void CameraInterface::get_pins()
}
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
int32_t ctrl_alloc = 0;
bool ctrl_alloc = false;
if (p_ctrl_alloc != PARAM_INVALID) {
param_get(p_ctrl_alloc, &ctrl_alloc);
}
if (ctrl_alloc == 1) {
if (ctrl_alloc) {
unsigned pin_index = 0;
for (unsigned i = 0; i < 16 && pin_index < arraySize(_pins); ++i) {
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_INT32(SENS_EN_ETSASPD, 0);
PARAM_DEFINE_BOOL(SENS_EN_ETSASPD, 0);
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_INT32(SENS_EN_MS4525, 0);
PARAM_DEFINE_BOOL(SENS_EN_MS4525, 0);
@@ -37,5 +37,5 @@
* @reboot_required true
* @group Sensors
* @boolean
*/
PARAM_DEFINE_INT32(SENS_EN_MS5525, 0);
**/
PARAM_DEFINE_BOOL(SENS_EN_MS5525, 0);
@@ -37,5 +37,5 @@
* @reboot_required true
* @group Sensors
* @boolean
*/
PARAM_DEFINE_INT32(SENS_EN_SDP3X, 0);
**/
PARAM_DEFINE_BOOL(SENS_EN_SDP3X, 0);
@@ -157,7 +157,7 @@ private:
perf_counter_t _sample_perf{perf_alloc(PC_COUNT, "mb12xx_sample_perf")};
DEFINE_PARAMETERS(
(ParamInt<px4::params::SENS_EN_MB12XX>) _p_sensor_enabled,
(ParamBool<px4::params::SENS_EN_MB12XX>) _p_sensor_enabled,
(ParamInt<px4::params::SENS_MB12_0_ROT>) _p_sensor0_rot,
(ParamInt<px4::params::SENS_MB12_1_ROT>) _p_sensor1_rot,
(ParamInt<px4::params::SENS_MB12_2_ROT>) _p_sensor2_rot,
@@ -39,7 +39,7 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_MB12XX, 0);
PARAM_DEFINE_BOOL(SENS_EN_MB12XX, 0);
/**
* MaxBotix MB12XX Sensor 0 Rotation
@@ -291,4 +291,4 @@ PARAM_DEFINE_INT32(SENS_MB12_10_ROT, 0);
* @value 6 Yaw 270°
* @value 7 Yaw 315°
*/
PARAM_DEFINE_INT32(SENS_MB12_11_ROT, 0);
PARAM_DEFINE_INT32(SENS_MB12_11_ROT, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_PGA460, 0);
PARAM_DEFINE_BOOL(SENS_EN_PGA460, 0);
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_INT32(SENS_EN_SR05, 0);
PARAM_DEFINE_BOOL(SENS_EN_SR05, 0);
+1 -1
View File
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_VL53L1X, 0);
PARAM_DEFINE_BOOL(SENS_EN_VL53L1X, 0);
+1 -3
View File
@@ -444,8 +444,6 @@ bool DShot::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
} else {
int telemetry_index = 0;
const uint32_t reversible_outputs = _mixing_output.reversibleOutputs();
for (int i = 0; i < (int)num_outputs; i++) {
uint16_t output = outputs[i];
@@ -454,7 +452,7 @@ bool DShot::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
// This is in terms of DShot values, code below is in terms of actuator_output
// Direction 1) 48 is the slowest, 1047 is the fastest.
// Direction 2) 1049 is the slowest, 2047 is the fastest.
if (_param_dshot_3d_enable.get() || (reversible_outputs & (1u << i))) {
if (_param_dshot_3d_enable.get()) {
if (output >= _param_dshot_3d_dead_l.get() && output <= _param_dshot_3d_dead_h.get()) {
output = DSHOT_DISARM_VALUE;
+1 -1
View File
@@ -268,7 +268,7 @@ void LinuxPWMOut::update_params()
// PWM_MAIN_REVx
{
sprintf(str, "%s_REV%u", prefix, i + 1);
int32_t pwm_rev = 0;
bool pwm_rev = false;
if (param_get(param_find(str), &pwm_rev) == PX4_OK) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
-1
View File
@@ -1,6 +1,5 @@
module_name: PWM Output
actuator_output:
add_reverse_range_param: true
output_groups:
- param_prefix: PWM_MAIN
channel_label: 'Channel'
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_PAW3902, 0);
PARAM_DEFINE_BOOL(SENS_EN_PAW3902, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_PMW3901, 0);
PARAM_DEFINE_BOOL(SENS_EN_PMW3901, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_EN_PX4FLOW, 0);
PARAM_DEFINE_BOOL(SENS_EN_PX4FLOW, 0);
+1 -1
View File
@@ -314,7 +314,7 @@ void PCA9685Wrapper::updatePWMParams()
if (param_h != PARAM_INVALID) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
int32_t pval = 0;
bool pval = false;
param_get(param_h, &pval);
reverse_pwm_mask &= (0xfffe << i); // clear this bit
reverse_pwm_mask |= (((uint16_t)(pval != 0)) << i); // set to new val
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_INT32(SENS_EN_INA226, 0);
PARAM_DEFINE_BOOL(SENS_EN_INA226, 0);
/**
* INA226 Power Monitor Config
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_INT32(SENS_EN_INA228, 0);
PARAM_DEFINE_BOOL(SENS_EN_INA228, 0);
/**
* INA228 Power Monitor Config
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_INT32(SENS_EN_INA238, 0);
PARAM_DEFINE_BOOL(SENS_EN_INA238, 0);
/**
* INA238 Power Monitor Max Current
@@ -58,6 +58,8 @@
#include <cstring>
static constexpr uint64_t reader_timeout_us = 1000000;
class Mavlink2Dev;
class RtpsDev;
class ReadBuffer;
@@ -118,7 +120,6 @@ perf_counter_t mavlink_messages_parsed_count;
perf_counter_t mavlink_bytes_parsed_count;
perf_counter_t rtps_messages_parsed_count;
perf_counter_t rtps_bytes_parsed_count;
perf_counter_t buffer_drops;
class ReadBuffer
{
@@ -133,8 +134,6 @@ public:
uint8_t buffer[1024] = {};
size_t buf_size = 0;
static const size_t BUFFER_THRESHOLD = sizeof(buffer) * 0.8;
// We keep track of the first Mavlink and Rtps packet in the buffer.
// If start and end are equal there is no packet.
size_t start_mavlink = 0;
@@ -147,30 +146,18 @@ public:
size_t bytes_received = 0;
size_t bytes_lost = 0;
size_t header_bytes_received = 0;
// To keep track of readers.
hrt_abstime last_mavlink_read = 0;
hrt_abstime last_rtps_read = 0;
};
int ReadBuffer::read(int fd)
{
if (buf_size > BUFFER_THRESHOLD) {
// Drop the buffer if it's too full. This is not expected to happen, but it might, if one of the readers
// is too slow. In that case it's best to make space for new data, otherwise the faster reader might
// busy-loop w/o getting new data.
perf_count(buffer_drops);
PX4_DEBUG("Buffer full, dropping: %zu %zu %zu %zu", start_mavlink, end_mavlink, start_rtps, end_rtps);
// Drop only as much as we have to
size_t num_remove = math::max(start_mavlink, start_rtps);
if (num_remove == 0) {
num_remove = buf_size;
}
remove(0, num_remove);
start_mavlink -= math::min(num_remove, start_mavlink);
end_mavlink -= math::min(num_remove, end_mavlink);
start_rtps -= math::min(num_remove, start_rtps);
end_rtps -= math::min(num_remove, end_rtps);
if (sizeof(buffer) == buf_size) {
// This happens if one consumer does not read the data, or not fast enough.
// TODO: add a mechanism to thrown away data if a user is no longer reading.
PX4_DEBUG("Buffer full: %zu %zu %zu %zu", start_mavlink, end_mavlink, start_rtps, end_rtps);
}
int bytes_available = 0;
@@ -277,6 +264,7 @@ protected:
int try_to_copy_data(char *buffer, size_t buflen, MessageType message_type);
void scan_for_packets();
void check_for_timeouts();
void cleanup();
void lock(enum Operation op)
@@ -554,6 +542,23 @@ void DevCommon::scan_for_packets()
}
void DevCommon::check_for_timeouts()
{
// If a reader has timed out, mark its data as read.
if (hrt_elapsed_time(&_read_buffer->last_mavlink_read) > reader_timeout_us) {
if (_read_buffer->start_mavlink < _read_buffer->end_mavlink) {
_read_buffer->start_mavlink = _read_buffer->end_mavlink;
}
}
if (hrt_elapsed_time(&_read_buffer->last_rtps_read) > reader_timeout_us) {
if (_read_buffer->start_rtps < _read_buffer->end_rtps) {
_read_buffer->start_rtps = _read_buffer->end_rtps;
}
}
}
void DevCommon::cleanup()
{
const bool mavlink_available = (_read_buffer->start_mavlink < _read_buffer->end_mavlink);
@@ -603,11 +608,14 @@ Mavlink2Dev::Mavlink2Dev(ReadBuffer *read_buffer)
ssize_t Mavlink2Dev::read(struct file *filp, char *buffer, size_t buflen)
{
_read_buffer->last_mavlink_read = hrt_absolute_time();
lock(Read);
// The cleanup needs to be right after a scan, so we don't clean up
// something that we haven't found yet.
scan_for_packets();
check_for_timeouts();
cleanup();
// If we have already a packet ready in the current buffer, we don't have
@@ -622,7 +630,7 @@ ssize_t Mavlink2Dev::read(struct file *filp, char *buffer, size_t buflen)
// Otherwise, we have to do a read.
ret = _read_buffer->read(_fd);
if (ret <= 0) {
if (ret < 0) {
unlock(Read);
return ret;
}
@@ -685,9 +693,12 @@ RtpsDev::RtpsDev(ReadBuffer *read_buffer)
ssize_t RtpsDev::read(struct file *filp, char *buffer, size_t buflen)
{
_read_buffer->last_rtps_read = hrt_absolute_time();
lock(Read);
scan_for_packets();
check_for_timeouts();
cleanup();
// If we have already a packet ready in the current buffer, we don't have to read.
@@ -701,7 +712,7 @@ ssize_t RtpsDev::read(struct file *filp, char *buffer, size_t buflen)
// Otherwise, we have to do a read.
ret = _read_buffer->read(_fd);
if (ret <= 0) {
if (ret < 0) {
unlock(Read);
return ret;
}
@@ -767,11 +778,10 @@ int protocol_splitter_main(int argc, char *argv[])
bytes_received_count = perf_alloc(PC_COUNT, "protocol_splitter: bytes received");
bytes_lost_count = perf_alloc(PC_COUNT, "protocol_splitter: bytes unused/lost");
header_bytes_received_count = perf_alloc(PC_COUNT, "protocol_splitter: header bytes received");
mavlink_messages_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: MAVLink msgs parsed");
mavlink_bytes_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: MAVLink msgs bytes parsed");
rtps_messages_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: RTPS msgs parsed");
rtps_bytes_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: RTPS msgs bytes parsed");
buffer_drops = perf_alloc(PC_COUNT, "protocol_splitter: buffer drops");
mavlink_messages_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: MAVLink messages parsed");
mavlink_bytes_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: MAVLink messages bytes parsed");
rtps_messages_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: RTPS messages parsed");
rtps_bytes_parsed_count = perf_alloc(PC_COUNT, "protocol_splitter: RTPS messages bytes parsed");
strncpy(objects->device_name, argv[2], sizeof(objects->device_name));
sem_init(&objects->r_lock, 1, 1);
@@ -814,7 +824,6 @@ int protocol_splitter_main(int argc, char *argv[])
perf_free(mavlink_bytes_parsed_count);
perf_free(rtps_messages_parsed_count);
perf_free(rtps_bytes_parsed_count);
perf_free(buffer_drops);
}
}
+89 -3
View File
@@ -222,6 +222,11 @@ int PWMOut::set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_
return OK;
}
int PWMOut::set_i2c_bus_clock(unsigned bus, unsigned clock_hz)
{
return device::I2C::set_bus_clock(bus, clock_hz);
}
void PWMOut::update_current_rate()
{
/*
@@ -650,7 +655,7 @@ void PWMOut::update_params()
// PWM_MAIN_REVx
{
sprintf(str, "%s_REV%u", prefix, i + 1);
int32_t pwm_rev = 0;
bool pwm_rev = false;
if (param_get(param_find(str), &pwm_rev) == PX4_OK) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
@@ -690,7 +695,7 @@ void PWMOut::update_params()
_num_disarmed_set = num_disarmed_set;
}
int PWMOut::ioctl(device::file_t *filp, int cmd, unsigned long arg)
int PWMOut::ioctl(file *filp, int cmd, unsigned long arg)
{
int ret = pwm_ioctl(filp, cmd, arg);
@@ -702,7 +707,7 @@ int PWMOut::ioctl(device::file_t *filp, int cmd, unsigned long arg)
return ret;
}
int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
int PWMOut::pwm_ioctl(file *filp, int cmd, unsigned long arg)
{
int ret = OK;
@@ -1089,6 +1094,34 @@ int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
return ret;
}
void PWMOut::sensor_reset(int ms)
{
if (ms < 1) {
ms = 1;
}
board_spi_reset(ms, 0xffff);
}
void PWMOut::peripheral_reset(int ms)
{
if (ms < 1) {
ms = 10;
}
board_peripheral_reset(ms);
}
namespace
{
int fmu_new_i2c_speed(unsigned bus, unsigned clock_hz)
{
return PWMOut::set_i2c_bus_clock(bus, clock_hz);
}
} // namespace
int PWMOut::test(const char *dev)
{
int fd;
@@ -1234,6 +1267,50 @@ int PWMOut::custom_command(int argc, char *argv[])
const char *verb = argv[myoptind];
/* does not operate on a FMU instance */
if (!strcmp(verb, "i2c")) {
if (argc > 2) {
int bus = strtol(argv[1], 0, 0);
int clock_hz = strtol(argv[2], 0, 0);
int ret = fmu_new_i2c_speed(bus, clock_hz);
if (ret) {
PX4_ERR("setting I2C clock failed");
}
return ret;
}
return print_usage("not enough arguments");
}
if (!strcmp(verb, "sensor_reset")) {
if (argc > 1) {
int reset_time = strtol(argv[1], nullptr, 0);
sensor_reset(reset_time);
} else {
sensor_reset(0);
PX4_INFO("reset default time");
}
return 0;
}
if (!strcmp(verb, "peripheral_reset")) {
if (argc > 2) {
int reset_time = strtol(argv[2], 0, 0);
peripheral_reset(reset_time);
} else {
peripheral_reset(0);
PX4_INFO("reset default time");
}
return 0;
}
/* start pwm_out if not running */
if (!is_running()) {
@@ -1317,6 +1394,15 @@ By default the module runs on a work queue with a callback on the uORB actuator_
PRINT_MODULE_USAGE_NAME("pwm_out", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_COMMAND_DESCR("sensor_reset", "Do a sensor reset (SPI bus)");
PRINT_MODULE_USAGE_ARG("<ms>", "Delay time in ms between reset and re-enabling", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("peripheral_reset", "Reset board peripherals");
PRINT_MODULE_USAGE_ARG("<ms>", "Delay time in ms between reset and re-enabling", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("i2c", "Configure I2C clock rate");
PRINT_MODULE_USAGE_ARG("<bus_id> <rate>", "Specify the bus id (>=0) and rate in Hz", false);
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test outputs");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();

Some files were not shown because too many files have changed in this diff Show More