mirror of https://github.com/ArduPilot/ardupilot
fix uint > int issue - for hil
This commit is contained in:
parent
4a4960eede
commit
651bd6953b
|
@ -252,9 +252,9 @@ RC_Channel::norm_input()
|
|||
float
|
||||
RC_Channel::norm_output()
|
||||
{
|
||||
uint16_t mid = (radio_max + radio_min) / 2;
|
||||
int16_t mid = (radio_max + radio_min) / 2;
|
||||
|
||||
if(radio_out < radio_trim)
|
||||
if(radio_out < mid)
|
||||
return (float)(radio_out - mid) / (float)(mid - radio_min);
|
||||
else
|
||||
return (float)(radio_out - mid) / (float)(radio_max - mid);
|
||||
|
|
Loading…
Reference in New Issue