mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Periph: fixed vsnprintf return assumption
This commit is contained in:
parent
6af9d55e70
commit
bc0b9337a0
@ -1093,7 +1093,7 @@ void can_printf(const char *fmt, ...)
|
|||||||
va_start(ap, fmt);
|
va_start(ap, fmt);
|
||||||
uint32_t n = vsnprintf(tbuf, sizeof(tbuf), fmt, ap);
|
uint32_t n = vsnprintf(tbuf, sizeof(tbuf), fmt, ap);
|
||||||
va_end(ap);
|
va_end(ap);
|
||||||
pkt.text.len = n;
|
pkt.text.len = MIN(n, sizeof(tbuf));
|
||||||
pkt.text.data = (uint8_t *)&tbuf[0];
|
pkt.text.data = (uint8_t *)&tbuf[0];
|
||||||
|
|
||||||
uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer);
|
uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer);
|
||||||
|
Loading…
Reference in New Issue
Block a user