AC_AttControl: add parameter check of throttle mix

This commit is contained in:
Randy Mackay 2016-09-01 20:31:49 +09:00
parent 535158e0d8
commit 44830be172
3 changed files with 22 additions and 0 deletions

View File

@ -234,6 +234,9 @@ public:
// Calculates the body frame angular velocities to follow the target attitude // Calculates the body frame angular velocities to follow the target attitude
void attitude_controller_run_quat(); void attitude_controller_run_quat();
// sanity check parameters. should be called once before take-off
virtual void parameter_sanity_check() {}
// User settable parameters // User settable parameters
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];

View File

@ -232,3 +232,19 @@ void AC_AttitudeControl_Multi::rate_controller_run()
control_monitor_update(); 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;
}
}

View File

@ -74,6 +74,9 @@ public:
// run lowest level body-frame rate controller and send outputs to the motors // run lowest level body-frame rate controller and send outputs to the motors
void rate_controller_run(); void rate_controller_run();
// sanity check parameters. should be called once before take-off
void parameter_sanity_check();
// user settable parameters // user settable parameters
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];