From 44830be1725c7752845b2bba750d08caaccb629c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 1 Sep 2016 20:31:49 +0900 Subject: [PATCH] AC_AttControl: add parameter check of throttle mix --- .../AC_AttitudeControl/AC_AttitudeControl.h | 3 +++ .../AC_AttitudeControl_Multi.cpp | 16 ++++++++++++++++ .../AC_AttitudeControl_Multi.h | 3 +++ 3 files changed, 22 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 439678b353..96cb5540d9 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -234,6 +234,9 @@ public: // Calculates the body frame angular velocities to follow the target attitude void attitude_controller_run_quat(); + // sanity check parameters. should be called once before take-off + virtual void parameter_sanity_check() {} + // User settable parameters static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 4ee93eecba..68788bf9bb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -232,3 +232,19 @@ void AC_AttitudeControl_Multi::rate_controller_run() control_monitor_update(); } + +// sanity check parameters. should be called once before takeoff +void AC_AttitudeControl_Multi::parameter_sanity_check() +{ + // sanity check throttle mix parameters + if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) { + _thr_mix_min = AC_ATTITUDE_CONTROL_MIN_DEFAULT; + } + if (_thr_mix_max < 0.5f || _thr_mix_max > 0.9f) { + _thr_mix_max = AC_ATTITUDE_CONTROL_MAX_DEFAULT; + } + if (_thr_mix_min > _thr_mix_max) { + _thr_mix_min = AC_ATTITUDE_CONTROL_MIN_DEFAULT; + _thr_mix_max = AC_ATTITUDE_CONTROL_MAX_DEFAULT; + } +} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index ca4085087b..ca2959dd02 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -74,6 +74,9 @@ public: // run lowest level body-frame rate controller and send outputs to the motors void rate_controller_run(); + // sanity check parameters. should be called once before take-off + void parameter_sanity_check(); + // user settable parameters static const struct AP_Param::GroupInfo var_info[];