mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: Match output type and variable type
This commit is contained in:
parent
88c681586f
commit
954e6a0c50
|
@ -169,7 +169,7 @@ void AP_RCProtocol_DSM::dsm_guess_format(bool reset, const uint8_t dsm_frame[16]
|
|||
}
|
||||
|
||||
/* 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);
|
||||
}
|
||||
|
||||
|
|
|
@ -296,7 +296,7 @@ void AP_RCProtocol_SUMD::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
|
||||
for (i = 4; i < _rxpacket.length; i++) {
|
||||
#ifdef SUMD_DEBUG
|
||||
hal.console->printf("ch[%d] : %x %x [ %x %d ]\n", i + 1, _rxpacket.sumd_data[i * 2 + 1], _rxpacket.sumd_data[i * 2 + 2],
|
||||
hal.console->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);
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue