mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: Match output type and variable type
This commit is contained in:
parent
b208b76884
commit
2e4dda5ece
|
@ -183,7 +183,7 @@ dsm_guess_format(bool reset, const uint8_t dsm_frame[16])
|
||||||
}
|
}
|
||||||
|
|
||||||
/* call ourselves to reset our state ... we have to try again */
|
/* call ourselves to reset our state ... we have to try again */
|
||||||
debug("DSM: format detect fail, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
|
debug("DSM: format detect fail, 10: 0x%08x %u 11: 0x%08x %u", cs10, votes10, cs11, votes11);
|
||||||
dsm_guess_format(true, dsm_frame);
|
dsm_guess_format(true, dsm_frame);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -349,7 +349,7 @@ int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channe
|
||||||
|
|
||||||
for (i = 4; i < _rxpacket.length; i++) {
|
for (i = 4; i < _rxpacket.length; i++) {
|
||||||
if (_debug) {
|
if (_debug) {
|
||||||
printf("ch[%d] : %x %x [ %x %d ]\n", i + 1, _rxpacket.sumd_data[i * 2 + 1], _rxpacket.sumd_data[i * 2 + 2],
|
printf("ch[%u] : %x %x [ %x %d ]\n", i + 1, _rxpacket.sumd_data[i * 2 + 1], _rxpacket.sumd_data[i * 2 + 2],
|
||||||
((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3,
|
((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3,
|
||||||
((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3);
|
((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue