AP_Motors: add AP_MOTORS_DENSITY_COMP_DISABLED option

This commit is contained in:
Jonathan Challinger 2016-01-22 10:41:19 -08:00 committed by Randy Mackay
parent 68cf1b6956
commit 9a09a86bb8
2 changed files with 6 additions and 0 deletions

View File

@ -333,10 +333,12 @@ float AP_MotorsMulticopter::get_compensation_gain() const
float ret = 1.0f / _lift_max;
#if AP_MOTORS_DENSITY_COMP == 1
// air density ratio is increasing in density / decreasing in altitude
if (_air_density_ratio > 0.3f && _air_density_ratio < 1.5f) {
ret *= 1.0f / constrain_float(_air_density_ratio,0.5f,1.25f);
}
#endif
return ret;
}

View File

@ -8,6 +8,10 @@
#include "AP_Motors_Class.h"
#ifndef AP_MOTORS_DENSITY_COMP
#define AP_MOTORS_DENSITY_COMP 1
#endif
#define AP_MOTORS_DEFAULT_MIN_THROTTLE 130
#define AP_MOTORS_DEFAULT_MID_THROTTLE 500
#define AP_MOTORS_DEFAULT_MAX_THROTTLE 1000