From 7de56d434caf9660ffb11e26b223e0899fda1ab9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 19 Jan 2024 20:48:27 +1100 Subject: [PATCH] Tools: fixed parameter names --- Tools/Frame_params/SkyWalkerX8.param | 2 +- Tools/Frame_params/SkyWalkerX8_ReverseThrust.param | 2 +- Tools/autotest/arduplane.py | 2 +- Tools/autotest/default_params/vee-gull 005.param | 2 +- Tools/autotest/quadplane.py | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/Frame_params/SkyWalkerX8.param b/Tools/Frame_params/SkyWalkerX8.param index df292fbbfd..93c21adb7a 100644 --- a/Tools/Frame_params/SkyWalkerX8.param +++ b/Tools/Frame_params/SkyWalkerX8.param @@ -30,7 +30,7 @@ LEVEL_ROLL_LIMIT,15 PITCH_LIM_MAX_DEG,15.00 PITCH_LIM_MIN_DEG,-25.00 ROLL_LIMIT_DEG,35.00 -MIN_GNDSPD_CM,600 +MIN_GROUNDSPEED,6 MIXING_GAIN,0.5 NAVL1_DAMPING,0.75 NAVL1_PERIOD,17 diff --git a/Tools/Frame_params/SkyWalkerX8_ReverseThrust.param b/Tools/Frame_params/SkyWalkerX8_ReverseThrust.param index 7f4c5b5fc5..1de10e3e1c 100644 --- a/Tools/Frame_params/SkyWalkerX8_ReverseThrust.param +++ b/Tools/Frame_params/SkyWalkerX8_ReverseThrust.param @@ -30,7 +30,7 @@ LEVEL_ROLL_LIMIT,15 PITCH_LIM_MAX_DEG,15.00 PITCH_LIM_MIN_DEG,-25.00 ROLL_LIMIT_DEG,35.00 -MIN_GNDSPD_CM,600 +MIN_GROUNDSPEED,6 MIXING_GAIN,0.5 NAVL1_DAMPING,0.75 NAVL1_PERIOD,17 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 3baf62bdbd..ca06437d13 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -845,7 +845,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): self.context_push() self.set_parameters({ "AIRSPEED_CRUISE": self.get_parameter("AIRSPEED_CRUISE"), - "MIN_GNDSPD_CM": self.get_parameter("MIN_GNDSPD_CM"), + "MIN_GROUNDSPEED": self.get_parameter("MIN_GROUNDSPEED"), "TRIM_THROTTLE": self.get_parameter("TRIM_THROTTLE"), }) diff --git a/Tools/autotest/default_params/vee-gull 005.param b/Tools/autotest/default_params/vee-gull 005.param index ed9db07113..5d062657a7 100644 --- a/Tools/autotest/default_params/vee-gull 005.param +++ b/Tools/autotest/default_params/vee-gull 005.param @@ -345,7 +345,7 @@ LOG_DISARMED,0 LOG_FILE_BUFSIZE,16 LOG_FILE_DSRMROT,0 LOG_REPLAY,0 -MIN_GNDSPD_CM,0 +MIN_GROUNDSPEED,0 MIS_RESTART,0 MIS_TOTAL,7 MIXING_GAIN,0.5 diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index a737364160..1207691fc7 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -817,7 +817,7 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite): self.set_parameter("STALL_PREVENTION", 0) thr_min_pwm = self.get_parameter("Q_M_PWM_MIN") - lim_roll_deg = self.get_parameter("LIM_ROLL_DEG") + lim_roll_deg = self.get_parameter("ROLL_LIMIT_DEG") self.progress("Waiting for motors to stop (transition completion)") self.wait_servo_channel_value(5, thr_min_pwm,