mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: Fix the issue of ST24 receiver not working
This commit is contained in:
parent
50525206d5
commit
b351644583
|
@ -177,6 +177,7 @@ void AP_RCProtocol_ST24::_process_byte(uint8_t byte)
|
||||||
values[chan_index] = (uint16_t)(values[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
|
values[chan_index] = (uint16_t)(values[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
|
||||||
chan_index++;
|
chan_index++;
|
||||||
}
|
}
|
||||||
|
add_input(num_values, values, false);//AP_RCProtocol: Fix the issue of ST24 receiver not working
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -207,6 +208,7 @@ void AP_RCProtocol_ST24::_process_byte(uint8_t byte)
|
||||||
values[chan_index] = (uint16_t)(values[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
|
values[chan_index] = (uint16_t)(values[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
|
||||||
chan_index++;
|
chan_index++;
|
||||||
}
|
}
|
||||||
|
add_input(num_values, values, false);//AP_RCProtocol: Fix the issue of ST24 receiver not working
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue