rc range bug fixed
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1058 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
9b3b5320fc
commit
718bf566c8
@ -157,7 +157,7 @@ RC_Channel::angle_to_pwm()
|
|||||||
int16_t
|
int16_t
|
||||||
RC_Channel::pwm_to_range()
|
RC_Channel::pwm_to_range()
|
||||||
{
|
{
|
||||||
return _low + _high * ((float)(radio_in - radio_min) / (float)(radio_max - radio_min));
|
return _low + ((_high - _low) * ((float)(radio_in - radio_min) / (float)(radio_max - radio_min)));
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t
|
int16_t
|
||||||
|
Loading…
Reference in New Issue
Block a user