From e9da278164b211d2b92ea041cc4f4308e068b060 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Feb 2023 23:44:42 +0000 Subject: [PATCH] AP_Motors: example: add script to run motor example at a range of head rooms and throttle average max values --- .../examples/AP_Motors_test/MotorTestSweep.sh | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100755 libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh diff --git a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh new file mode 100755 index 0000000000..fb972b77dc --- /dev/null +++ b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh @@ -0,0 +1,26 @@ +# Build and run the motors example stability test at a range of yaw headroom and throttle average max values +# Output results to files for comparison + +cd "$(dirname "$0")" +cd ../../../.. + +mkdir -p MotorTestSweep + +./waf configure --board linux +./waf build --target examples/AP_Motors_test +echo + +YAW_HEADROOM="0 100 200 300 400 500 600 700 800 900 1000" +THR_AVERAGE_MAX="0 0.1 0.2 0.3 0.4 0.5 0.6 0.7 0.8 0.9 1.0" + +COUNTER=0 +for headroom in $YAW_HEADROOM; do + echo "Yaw Headroom: $headroom" + for Thr in $THR_AVERAGE_MAX; do + echo " Throttle average max: $Thr" + ./build/linux/examples/AP_Motors_test s yaw_headroom=$headroom throttle_avg_max=$Thr > MotorTestSweep/$COUNTER.csv + let COUNTER++ + done + echo +done +