diff --git a/.ci/Jenkinsfile-hardware b/.ci/Jenkinsfile-hardware index aa360d81f8..5c4c0c9b7e 100644 --- a/.ci/Jenkinsfile-hardware +++ b/.ci/Jenkinsfile-hardware @@ -771,8 +771,6 @@ void checkStatus() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf latency"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ps"' - sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output0"' - sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output1" || true' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm_out status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "top once"' diff --git a/Tools/HIL/test_airframes.sh b/Tools/HIL/test_airframes.sh index 2119d09034..14658241fe 100755 --- a/Tools/HIL/test_airframes.sh +++ b/Tools/HIL/test_airframes.sh @@ -54,8 +54,6 @@ do ${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'ps' ${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'work_queue status' - ${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'pwm info' - ${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'mavlink stop-all' ${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'gps stop' diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index 8e8a89f8e6..57b202a3ea 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -89,7 +89,6 @@ 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 diff --git a/boards/ark/cannode/default.px4board b/boards/ark/cannode/default.px4board index a92adda6c3..300da12bde 100644 --- a/boards/ark/cannode/default.px4board +++ b/boards/ark/cannode/default.px4board @@ -31,6 +31,5 @@ CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/av/x-v1/default.px4board b/boards/av/x-v1/default.px4board index cfdf80f844..0665aa8b06 100644 --- a/boards/av/x-v1/default.px4board +++ b/boards/av/x-v1/default.px4board @@ -86,7 +86,6 @@ CONFIG_SYSTEMCMDS_NETMAN=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 diff --git a/boards/beaglebone/blue/default.px4board b/boards/beaglebone/blue/default.px4board index b66648fc80..5a16050b54 100644 --- a/boards/beaglebone/blue/default.px4board +++ b/boards/beaglebone/blue/default.px4board @@ -63,7 +63,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MOTOR_TEST=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SHUTDOWN=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y diff --git a/boards/bitcraze/crazyflie/default.px4board b/boards/bitcraze/crazyflie/default.px4board index b061cf4b28..a407eb27fe 100644 --- a/boards/bitcraze/crazyflie/default.px4board +++ b/boards/bitcraze/crazyflie/default.px4board @@ -38,7 +38,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_TOP=y diff --git a/boards/bitcraze/crazyflie21/default.px4board b/boards/bitcraze/crazyflie21/default.px4board index 8abc2182d1..9f2e37f8f1 100644 --- a/boards/bitcraze/crazyflie21/default.px4board +++ b/boards/bitcraze/crazyflie21/default.px4board @@ -37,7 +37,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index 0e8c51c25e..d37ee80107 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -92,7 +92,6 @@ 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_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index 1d4c518875..e2d2002b1f 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -93,7 +93,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index 9f929c9888..8671d375d6 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -87,7 +87,6 @@ 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 diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 27e7607c28..a42ef27c38 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -90,7 +90,6 @@ 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 diff --git a/boards/diatone/mamba-f405-mk2/default.px4board b/boards/diatone/mamba-f405-mk2/default.px4board index 8a26846ea6..7fcd4a1a81 100644 --- a/boards/diatone/mamba-f405-mk2/default.px4board +++ b/boards/diatone/mamba-f405-mk2/default.px4board @@ -41,6 +41,5 @@ CONFIG_SYSTEMCMDS_MFT=y CONFIG_SYSTEMCMDS_MTD=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_VER=y diff --git a/boards/emlid/navio2/default.px4board b/boards/emlid/navio2/default.px4board index 6964c32794..ecd456c352 100644 --- a/boards/emlid/navio2/default.px4board +++ b/boards/emlid/navio2/default.px4board @@ -65,7 +65,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MOTOR_TEST=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SHUTDOWN=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index 028a92bf9b..227a57e913 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -85,7 +85,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/holybro/kakutef7/default.px4board b/boards/holybro/kakutef7/default.px4board index ccab89c6f2..455d95d091 100644 --- a/boards/holybro/kakutef7/default.px4board +++ b/boards/holybro/kakutef7/default.px4board @@ -34,4 +34,3 @@ CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_SENSORS=y # CONFIG_SENSORS_VEHICLE_AIRSPEED is not set CONFIG_SYSTEMCMDS_PARAM=y -CONFIG_SYSTEMCMDS_PWM=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index 7304aa2982..c1e3ace14c 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -78,7 +78,6 @@ CONFIG_SYSTEMCMDS_MOTOR_TEST=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 92b6f5fbdb..7b007055f5 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -95,7 +95,6 @@ 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 diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board index e624cd08f1..a9069bb741 100644 --- a/boards/matek/h743-mini/default.px4board +++ b/boards/matek/h743-mini/default.px4board @@ -73,7 +73,6 @@ CONFIG_SYSTEMCMDS_MTD=n CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=n CONFIG_SYSTEMCMDS_SD_STRESS=n diff --git a/boards/matek/h743-slim/default.px4board b/boards/matek/h743-slim/default.px4board index fe8f702a52..bcff78646b 100644 --- a/boards/matek/h743-slim/default.px4board +++ b/boards/matek/h743-slim/default.px4board @@ -72,7 +72,6 @@ CONFIG_SYSTEMCMDS_MTD=n CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=n CONFIG_SYSTEMCMDS_SD_STRESS=n diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index fe8f702a52..bcff78646b 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -72,7 +72,6 @@ CONFIG_SYSTEMCMDS_MTD=n CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=n CONFIG_SYSTEMCMDS_SD_STRESS=n diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index 3437c6d9b9..16f863844e 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -91,7 +91,6 @@ 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 diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index d64d4f43a7..164fc9fbcf 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -86,7 +86,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index 25dc314ade..5da6d75bf0 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -87,7 +87,6 @@ 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 diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index 2e06b96802..815b3903cf 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -88,7 +88,6 @@ 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 diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index 77f006f3b1..5e0733f474 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -88,7 +88,6 @@ 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 diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index 25dc314ade..5da6d75bf0 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -87,7 +87,6 @@ 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 diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index c5881e8c8a..a80c4608b5 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -88,7 +88,6 @@ 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 diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index a5c2a9682a..9eb74db5fe 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -87,7 +87,6 @@ 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 diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index 978c8386d5..a4fdf02fc0 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -89,7 +89,6 @@ 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 diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index 243d1e8780..95fa5e3b05 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -89,7 +89,6 @@ 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 diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index 18f465678b..575deb5601 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -83,7 +83,6 @@ 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 diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index 2419873d62..417bc2ba8b 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -88,7 +88,6 @@ 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 diff --git a/boards/nxp/fmurt1062-v1/default.px4board b/boards/nxp/fmurt1062-v1/default.px4board index 099529b03e..5c82e73ea3 100644 --- a/boards/nxp/fmurt1062-v1/default.px4board +++ b/boards/nxp/fmurt1062-v1/default.px4board @@ -60,7 +60,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/nxp/ucans32k146/default.px4board b/boards/nxp/ucans32k146/default.px4board index 758860694a..9b747e705e 100644 --- a/boards/nxp/ucans32k146/default.px4board +++ b/boards/nxp/ucans32k146/default.px4board @@ -21,7 +21,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MFT=y CONFIG_SYSTEMCMDS_MTD=y CONFIG_SYSTEMCMDS_PARAM=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y diff --git a/boards/omnibus/f4sd/default.px4board b/boards/omnibus/f4sd/default.px4board index 241deb0272..3c5dacf2f4 100644 --- a/boards/omnibus/f4sd/default.px4board +++ b/boards/omnibus/f4sd/default.px4board @@ -35,4 +35,3 @@ CONFIG_MODULES_SENSORS=y # CONFIG_SENSORS_VEHICLE_AIRSPEED is not set CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y CONFIG_SYSTEMCMDS_PARAM=y -CONFIG_SYSTEMCMDS_PWM=y diff --git a/boards/px4/fmu-v2/default.px4board b/boards/px4/fmu-v2/default.px4board index c11fd31688..fcc55066ad 100644 --- a/boards/px4/fmu-v2/default.px4board +++ b/boards/px4/fmu-v2/default.px4board @@ -40,7 +40,6 @@ CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y CONFIG_SYSTEMCMDS_MFT=y CONFIG_SYSTEMCMDS_MTD=y CONFIG_SYSTEMCMDS_PARAM=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y CONFIG_SYSTEMCMDS_VER=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 7fb2edbcf9..3786cea4a1 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -92,7 +92,6 @@ 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 diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index bc42098768..5de0f6f91c 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -93,7 +93,6 @@ 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 diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index cd4a44f4a6..e3944b69a5 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -90,7 +90,6 @@ 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 diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index 603c2f4e05..8eaf2bcd00 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -96,7 +96,6 @@ 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 diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index e330afce89..51205b6bfa 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -99,7 +99,6 @@ CONFIG_SYSTEMCMDS_NETMAN=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 diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index 03a70c970b..6e0d2ef9a2 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -77,7 +77,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SERIAL_TEST=y diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index f9e57b24fb..5d02c8c249 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -88,7 +88,6 @@ 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_SD_BENCH=y CONFIG_SYSTEMCMDS_SD_STRESS=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 9250be421d..3d16e4505e 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_NETMAN=y CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y diff --git a/boards/px4/raspberrypi/default.px4board b/boards/px4/raspberrypi/default.px4board index 45d7dc1d41..1b266a0550 100644 --- a/boards/px4/raspberrypi/default.px4board +++ b/boards/px4/raspberrypi/default.px4board @@ -62,7 +62,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MOTOR_TEST=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SHUTDOWN=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index 645734c92a..6c10810f53 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -51,7 +51,6 @@ CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_MOTOR_TEST=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SHUTDOWN=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y diff --git a/boards/raspberrypi/pico/default.px4board b/boards/raspberrypi/pico/default.px4board index ed93091a03..3fda4b16f8 100644 --- a/boards/raspberrypi/pico/default.px4board +++ b/boards/raspberrypi/pico/default.px4board @@ -41,7 +41,6 @@ CONFIG_SYSTEMCMDS_MOTOR_TEST=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_TOP=y diff --git a/boards/scumaker/pilotpi/default.px4board b/boards/scumaker/pilotpi/default.px4board index 022fb0d244..1bcdba8064 100644 --- a/boards/scumaker/pilotpi/default.px4board +++ b/boards/scumaker/pilotpi/default.px4board @@ -59,7 +59,6 @@ CONFIG_SYSTEMCMDS_DYN=y CONFIG_SYSTEMCMDS_LED_CONTROL=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y -CONFIG_SYSTEMCMDS_PWM=y CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_SHUTDOWN=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index 04c1d706fc..164884a010 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -91,7 +91,6 @@ CONFIG_SYSTEMCMDS_NETMAN=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 diff --git a/boards/spracing/h7extreme/default.px4board b/boards/spracing/h7extreme/default.px4board index beb349581d..d0286f373e 100644 --- a/boards/spracing/h7extreme/default.px4board +++ b/boards/spracing/h7extreme/default.px4board @@ -51,7 +51,6 @@ CONFIG_SYSTEMCMDS_MOTOR_TEST=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 diff --git a/boards/uvify/core/default.px4board b/boards/uvify/core/default.px4board index f1626adfe6..7dc5db41a9 100644 --- a/boards/uvify/core/default.px4board +++ b/boards/uvify/core/default.px4board @@ -74,7 +74,6 @@ 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 diff --git a/posix-configs/rpi/px4_test.config b/posix-configs/rpi/px4_test.config index 74c6643b3b..77a253157c 100644 --- a/posix-configs/rpi/px4_test.config +++ b/posix-configs/rpi/px4_test.config @@ -78,8 +78,6 @@ mavlink status streams sleep 1 param status sleep 1 -pwm info -sleep 1 sensors status sleep 1 perf diff --git a/src/systemcmds/pwm/CMakeLists.txt b/src/systemcmds/pwm/CMakeLists.txt deleted file mode 100644 index 859ce1c8d3..0000000000 --- a/src/systemcmds/pwm/CMakeLists.txt +++ /dev/null @@ -1,42 +0,0 @@ -############################################################################ -# -# Copyright (c) 2015 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ -px4_add_module( - MODULE systemcmds__pwm - MAIN pwm - COMPILE_FLAGS - -Wno-array-bounds - SRCS - pwm.cpp - DEPENDS - ) - diff --git a/src/systemcmds/pwm/Kconfig b/src/systemcmds/pwm/Kconfig deleted file mode 100644 index f09c865baf..0000000000 --- a/src/systemcmds/pwm/Kconfig +++ /dev/null @@ -1,12 +0,0 @@ -menuconfig SYSTEMCMDS_PWM - bool "pwm" - default n - ---help--- - Enable support for pwm - -menuconfig USER_PWM - bool "pwm running as userspace module" - default n - depends on BOARD_PROTECTED && SYSTEMCMDS_PWM - ---help--- - Put pwm in userspace memory diff --git a/src/systemcmds/pwm/pwm.cpp b/src/systemcmds/pwm/pwm.cpp deleted file mode 100644 index fcd3b37f9b..0000000000 --- a/src/systemcmds/pwm/pwm.cpp +++ /dev/null @@ -1,615 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013, 2014, 2017, 2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file pwm.cpp - * - * PWM servo output configuration and monitoring tool. - */ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#ifdef __PX4_NUTTX -#include -#endif - -#include "systemlib/err.h" -#include -#include "drivers/drv_pwm_output.h" - -static void usage(const char *reason); -__BEGIN_DECLS -__EXPORT int pwm_main(int argc, char *argv[]); -__END_DECLS - - -static void -usage(const char *reason) -{ - if (reason != nullptr) { - PX4_WARN("%s", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This command is used to configure PWM outputs for servo and ESC control. - -The default device `/dev/pwm_output0` are the Main channels, AUX channels are on `/dev/pwm_output1` (`-d` parameter). - -It is used in the startup script to make sure the PWM parameters (`PWM_*`) are applied (or the ones provided -by the airframe config if specified). `pwm status` shows the current settings (the trim value is an offset -and configured with `PWM_MAIN_TRIMx` and `PWM_AUX_TRIMx`). - -The disarmed value should be set such that the motors don't spin (it's also used for the kill switch), at the -minimum value they should spin. - -Channels are assigned to a group. Due to hardware limitations, the update rate can only be set per group. Use -`pwm status` to display the groups. If the `-c` argument is used, all channels of any included group must be included. - -The parameters `-p` and `-r` can be set to a parameter instead of specifying an integer: use -p p:PWM_MIN for example. - -Note that in OneShot mode, the PWM range [1000, 2000] is automatically mapped to [125, 250]. - -### Examples - -Set the PWM rate for all channels to 400 Hz: -$ pwm rate -a -r 400 - -Arm and set the outputs of channels 1 and 3 to a PWM value to 1200 us: -$ pwm min -c 13 -p 1200 - -)DESCR_STR"); - - - PRINT_MODULE_USAGE_NAME("pwm", "command"); - PRINT_MODULE_USAGE_COMMAND_DESCR("arm", "Arm output"); - PRINT_MODULE_USAGE_COMMAND_DESCR("disarm", "Disarm output"); - - PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print current configuration of all channels"); - - PRINT_MODULE_USAGE_COMMAND_DESCR("rate", "Configure PWM rates"); - PRINT_MODULE_USAGE_PARAM_INT('r', -1, 50, 400, "PWM Rate in Hz (0 = Oneshot, otherwise 50 to 400Hz)", false); - - PRINT_MODULE_USAGE_COMMAND_DESCR("oneshot", "Configure Oneshot125 (rate is set to 0)"); - - PRINT_MODULE_USAGE_COMMAND_DESCR("min", "Set Minimum PWM value"); - PRINT_MODULE_USAGE_COMMAND_DESCR("max", "Set Maximum PWM value"); - - PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'min' and 'max' require a PWM value:"); - PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 4000, "PWM value (eg. 1100)", false); - - PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'rate', 'oneshot', 'min', 'max' " - "additionally require to specify the channels with one of the following commands:"); - PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, nullptr, "select channels in the form: 1234 (1 digit per channel, 1=first)", - true); - PRINT_MODULE_USAGE_PARAM_INT('m', -1, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true); - PRINT_MODULE_USAGE_PARAM_INT('g', -1, 0, 10, "Select channels by group (eg. 0, 1, 2. use 'pwm status' to show groups)", - true); - PRINT_MODULE_USAGE_PARAM_FLAG('a', "Select all channels", true); - - PRINT_MODULE_USAGE_PARAM_COMMENT("These parameters apply to all commands:"); - PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/pwm_output0", "", "Select PWM output device", true); - PRINT_MODULE_USAGE_PARAM_FLAG('v', "Verbose output", true); - PRINT_MODULE_USAGE_PARAM_FLAG('e', "Exit with 1 instead of 0 on error", true); - -} - -int -pwm_main(int argc, char *argv[]) -{ - const char *dev = PWM_OUTPUT0_DEVICE_PATH; - int alt_rate = -1; // Default to indicate not set. - uint32_t alt_channel_groups = 0; - bool alt_channels_set = false; - bool print_verbose = false; - bool error_on_warn = false; - bool oneshot = false; - int ch; - int ret; - - char *ep; - uint32_t set_mask = 0; - unsigned group; - unsigned long channels; - unsigned single_ch = 0; - int pwm_value = 0; - - if (argc < 2) { - usage(nullptr); - return 1; - } - - int myoptind = 1; - const char *myoptarg = nullptr; - - while ((ch = px4_getopt(argc, argv, "d:vec:g:m:ap:r:", &myoptind, &myoptarg)) != EOF) { - switch (ch) { - - case 'd': - if (nullptr == strstr(myoptarg, "/dev/")) { - PX4_WARN("device %s not valid", myoptarg); - usage(nullptr); - return 1; - } - - dev = myoptarg; - break; - - case 'v': - print_verbose = true; - break; - - case 'e': - error_on_warn = true; - break; - - case 'c': - /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ - channels = strtoul(myoptarg, &ep, 0); - - while ((single_ch = channels % 10)) { - - set_mask |= 1 << (single_ch - 1); - channels /= 10; - } - - break; - - case 'g': - group = strtoul(myoptarg, &ep, 0); - - if ((*ep != '\0') || (group >= 32)) { - usage("bad channel_group value"); - return 1; - } - - alt_channel_groups |= (1 << group); - alt_channels_set = true; - break; - - case 'm': - /* Read in mask directly */ - set_mask = strtoul(myoptarg, &ep, 0); - - if (*ep != '\0') { - usage("BAD set_mask VAL"); - return 1; - } - - break; - - case 'a': - for (unsigned i = 0; i < PWM_OUTPUT_MAX_CHANNELS; i++) { - set_mask |= 1 << i; - } - - break; - - case 'p': - if (px4_get_parameter_value(myoptarg, pwm_value) != 0) { - PX4_ERR("CLI argument parsing for PWM value failed"); - return 1; - } - break; - - case 'r': - if (px4_get_parameter_value(myoptarg, alt_rate) != 0) { - PX4_ERR("CLI argument parsing for PWM rate failed"); - return 1; - } - break; - - default: - usage(nullptr); - return 1; - } - } - - if (myoptind >= argc) { - usage(nullptr); - return 1; - } - - const char *command = argv[myoptind]; - - if (print_verbose && set_mask > 0) { - PX4_INFO("Channels: "); - printf(" "); - - for (unsigned i = 0; i < PWM_OUTPUT_MAX_CHANNELS; i++) { - if (set_mask & 1 << i) { - printf("%u ", i + 1); - } - } - - printf("\n"); - } - - /* open for ioctl only */ - int fd = px4_open(dev, 0); - - if (fd < 0) { - PX4_ERR("can't open %s", dev); - return 1; - } - - /* get the number of servo channels */ - unsigned servo_count; - ret = px4_ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_COUNT"); - return error_on_warn; - } - - oneshot = !strcmp(command, "oneshot"); - - if (!strcmp(command, "arm")) { - /* tell safety that its ok to disable it with the switch */ - ret = px4_ioctl(fd, PWM_SERVO_SET_ARM_OK, 0); - - if (ret != OK) { - err(1, "PWM_SERVO_SET_ARM_OK"); - } - - /* tell IO that the system is armed (it will output values if safety is off) */ - ret = px4_ioctl(fd, PWM_SERVO_ARM, 0); - - if (ret != OK) { - err(1, "PWM_SERVO_ARM"); - } - - if (print_verbose) { - PX4_INFO("Outputs armed"); - } - - return 0; - - } else if (!strcmp(command, "disarm")) { - /* disarm, but do not revoke the SET_ARM_OK flag */ - ret = px4_ioctl(fd, PWM_SERVO_DISARM, 0); - - if (ret != OK) { - err(1, "PWM_SERVO_DISARM"); - } - - if (print_verbose) { - PX4_INFO("Outputs disarmed"); - } - - return 0; - - } else if (oneshot || !strcmp(command, "rate")) { - - /* Change alternate PWM rate or set oneshot - * Either the "oneshot" command was used - * and/OR -r was provided on command line and has changed the alt_rate - * to the non default of -1, so we will issue the PWM_SERVO_SET_UPDATE_RATE - * ioctl - */ - - if (oneshot || alt_rate >= 0) { - ret = px4_ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, oneshot ? 0 : alt_rate); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_SET_UPDATE_RATE (check rate for sanity)"); - return error_on_warn; - } - } - - /* directly supplied channel mask */ - if (set_mask > 0) { - ret = px4_ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, set_mask); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_SET_SELECT_UPDATE_RATE"); - return error_on_warn; - } - } - - /* assign alternate rate to channel groups */ - if (alt_channels_set) { - uint32_t mask = 0; - - for (group = 0; group < 32; group++) { - if ((1 << group) & alt_channel_groups) { - uint32_t group_mask; - - ret = px4_ioctl(fd, PWM_SERVO_GET_RATEGROUP(group), (unsigned long)&group_mask); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_RATEGROUP(%u)", group); - return error_on_warn; - } - - mask |= group_mask; - } - } - - ret = px4_ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, mask); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_SET_SELECT_UPDATE_RATE"); - return error_on_warn; - } - } - - return 0; - - } else if (!strcmp(command, "min")) { - - if (set_mask == 0) { - usage("min: no channels set"); - return 1; - } - - if (pwm_value < 0) { - return 0; - } - - if (pwm_value == 0) { - usage("min: no PWM value provided"); - return 1; - } - - struct pwm_output_values pwm_values {}; - - pwm_values.channel_count = servo_count; - - /* first get current state before modifying it */ - ret = px4_ioctl(fd, PWM_SERVO_GET_MIN_PWM, (long unsigned int)&pwm_values); - - if (ret != OK) { - PX4_ERR("failed get min values"); - return 1; - } - - for (unsigned i = 0; i < servo_count; i++) { - if (set_mask & 1 << i) { - pwm_values.values[i] = pwm_value; - - if (print_verbose) { - PX4_INFO("Channel %d: min PWM: %d", i + 1, pwm_value); - } - } - } - - if (pwm_values.channel_count == 0) { - usage("min: no channels provided"); - return 1; - - } else { - - ret = px4_ioctl(fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values); - - if (ret != OK) { - PX4_ERR("failed setting min values (%d)", ret); - return error_on_warn; - } - } - - return 0; - - } else if (!strcmp(command, "max")) { - - if (set_mask == 0) { - usage("no channels set"); - return 1; - } - - if (pwm_value < 0) { - return 0; - } - - if (pwm_value == 0) { - usage("no PWM value provided"); - return 1; - } - - struct pwm_output_values pwm_values {}; - - pwm_values.channel_count = servo_count; - - /* first get current state before modifying it */ - ret = px4_ioctl(fd, PWM_SERVO_GET_MAX_PWM, (long unsigned int)&pwm_values); - - if (ret != OK) { - PX4_ERR("failed get max values"); - return 1; - } - - for (unsigned i = 0; i < servo_count; i++) { - if (set_mask & 1 << i) { - pwm_values.values[i] = pwm_value; - - if (print_verbose) { - PX4_INFO("Channel %d: max PWM: %d", i + 1, pwm_value); - } - } - } - - if (pwm_values.channel_count == 0) { - usage("max: no PWM channels"); - return 1; - - } else { - - ret = px4_ioctl(fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values); - - if (ret != OK) { - PX4_ERR("failed setting max values (%d)", ret); - return error_on_warn; - } - } - - return 0; - - } else if (!strcmp(command, "status") || !strcmp(command, "info")) { - - printf("device: %s\n", dev); - - uint32_t info_default_rate; - uint32_t info_alt_rate; - uint32_t info_alt_rate_mask; - - ret = px4_ioctl(fd, PWM_SERVO_GET_DEFAULT_UPDATE_RATE, (unsigned long)&info_default_rate); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_DEFAULT_UPDATE_RATE"); - return 1; - } - - ret = px4_ioctl(fd, PWM_SERVO_GET_UPDATE_RATE, (unsigned long)&info_alt_rate); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_UPDATE_RATE"); - return 1; - } - - ret = px4_ioctl(fd, PWM_SERVO_GET_SELECT_UPDATE_RATE, (unsigned long)&info_alt_rate_mask); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_SELECT_UPDATE_RATE"); - return 1; - } - - struct pwm_output_values failsafe_pwm; - - struct pwm_output_values disarmed_pwm; - - struct pwm_output_values min_pwm; - - struct pwm_output_values max_pwm; - - ret = px4_ioctl(fd, PWM_SERVO_GET_FAILSAFE_PWM, (unsigned long)&failsafe_pwm); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_FAILSAFE_PWM"); - return 1; - } - - ret = px4_ioctl(fd, PWM_SERVO_GET_DISARMED_PWM, (unsigned long)&disarmed_pwm); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_DISARMED_PWM"); - return 1; - } - - ret = px4_ioctl(fd, PWM_SERVO_GET_MIN_PWM, (unsigned long)&min_pwm); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_MIN_PWM"); - return 1; - } - - ret = px4_ioctl(fd, PWM_SERVO_GET_MAX_PWM, (unsigned long)&max_pwm); - - if (ret != OK) { - PX4_ERR("PWM_SERVO_GET_MAX_PWM"); - return 1; - } - - /* print current servo values */ - for (unsigned i = 0; i < servo_count; i++) { - servo_position_t spos; - - ret = px4_ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&spos); - - if (ret == OK) { - printf("channel %u: %" PRIu16 " us", i + 1, spos); - - if (info_alt_rate_mask & (1 << i)) { - printf(" (alternative rate: %" PRIu32 " Hz", info_alt_rate); - - } else { - printf(" (default rate: %" PRIu32 " Hz", info_default_rate); - } - - - printf(" failsafe: %d, disarmed: %" PRIu16 " us, min: %" PRIu16 " us, max: %" PRIu16 " us)", - failsafe_pwm.values[i], disarmed_pwm.values[i], min_pwm.values[i], max_pwm.values[i]); - printf("\n"); - - } else { - printf("%u: ERROR\n", i); - } - } - - /* print rate groups */ - for (unsigned i = 0; i < servo_count; i++) { - uint32_t group_mask; - - ret = px4_ioctl(fd, PWM_SERVO_GET_RATEGROUP(i), (unsigned long)&group_mask); - - if (ret != OK) { - break; - } - - if (group_mask != 0) { - printf("channel group %u: channels", i); - - for (unsigned j = 0; j < 32; j++) { - if (group_mask & (1 << j)) { - printf(" %u", j + 1); - } - } - - printf("\n"); - } - } - - return 0; - } - - usage(nullptr); - return 0; -}