AP_MotorsMulticopter: add get_hover_throttle_as_high_end_pct

Returns hover throttle as a number from 0 to 1 in the range from throttle_min to throttle_max
This commit is contained in:
Leonard Hall 2015-12-19 12:35:26 +09:00 committed by Randy Mackay
parent e625c105a4
commit 49819d822f
2 changed files with 4 additions and 5 deletions

View File

@ -333,10 +333,9 @@ void AP_MotorsMulticopter::update_throttle_rpy_mix()
_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, 1.0f);
}
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
int16_t AP_MotorsMulticopter::get_hover_throttle_as_pwm() const
float AP_MotorsMulticopter::get_hover_throttle_as_high_end_pct() const
{
return (_throttle_radio_min + (float)(_throttle_radio_max - _throttle_radio_min) * _hover_out / 1000.0f);
return ((float)_hover_out / (1000.0f - _min_throttle));
}
float AP_MotorsMulticopter::get_compensation_gain() const

View File

@ -122,8 +122,8 @@ protected:
// return gain scheduling gain based on voltage and air density
float get_compensation_gain() const;
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
int16_t get_hover_throttle_as_pwm() const;
// get_hover_throttle_as_high_end_pct - return hover throttle in the 0 to 1 range
float get_hover_throttle_as_high_end_pct() const;
float rel_pwm_to_thr_range(float pwm) const;
float thr_range_to_rel_pwm(float thr) const;