From 9a09a86bb8c4dc261ac22789709b003e1fd5ff3e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 22 Jan 2016 10:41:19 -0800 Subject: [PATCH] AP_Motors: add AP_MOTORS_DENSITY_COMP_DISABLED option --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 ++ libraries/AP_Motors/AP_MotorsMulticopter.h | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 3cac7c2786..6d5944d6d0 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -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; } diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 65b6b4d6d2..632f8e4c90 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -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