Browse Source

AP_Motors: add AP_MOTORS_DENSITY_COMP_DISABLED option

mission-4.1.18
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
9a09a86bb8
  1. 2
      libraries/AP_Motors/AP_MotorsMulticopter.cpp
  2. 4
      libraries/AP_Motors/AP_MotorsMulticopter.h

2
libraries/AP_Motors/AP_MotorsMulticopter.cpp

@ -333,10 +333,12 @@ float AP_MotorsMulticopter::get_compensation_gain() const @@ -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;
}

4
libraries/AP_Motors/AP_MotorsMulticopter.h

@ -8,6 +8,10 @@ @@ -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

Loading…
Cancel
Save