fix uint > int issue - for hil

This commit is contained in:
Michael Oborne 2012-02-11 11:35:59 +08:00
parent be079c4fe8
commit 8ec192cf45
1 changed files with 3 additions and 3 deletions

View File

@ -252,9 +252,9 @@ RC_Channel::norm_input()
float
RC_Channel::norm_output()
{
uint16_t mid = (radio_max + radio_min) / 2;
if(radio_out < radio_trim)
int16_t mid = (radio_max + radio_min) / 2;
if(radio_out < mid)
return (float)(radio_out - mid) / (float)(mid - radio_min);
else
return (float)(radio_out - mid) / (float)(radio_max - mid);