mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Bootloader: remove redundant DroneCAN packet buffer initialization
The <msg>_encode method always zeros the buffer up to <msg>_MAX_SIZE bytes so there is no need to do it before calling the function. Saves at least 8 bytes per instance.
This commit is contained in:
parent
d48f9ef12c
commit
308ee11ca2
@ -139,7 +139,7 @@ static uint32_t get_random_range(uint16_t range)
|
|||||||
static void handle_get_node_info(CanardInstance* ins,
|
static void handle_get_node_info(CanardInstance* ins,
|
||||||
CanardRxTransfer* transfer)
|
CanardRxTransfer* transfer)
|
||||||
{
|
{
|
||||||
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
|
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
|
||||||
uavcan_protocol_GetNodeInfoResponse pkt {};
|
uavcan_protocol_GetNodeInfoResponse pkt {};
|
||||||
|
|
||||||
node_status.uptime_sec = AP_HAL::millis() / 1000U;
|
node_status.uptime_sec = AP_HAL::millis() / 1000U;
|
||||||
@ -868,7 +868,7 @@ void can_printf(const char *fmt, ...)
|
|||||||
// only on H7 for now, where we have plenty of flash
|
// only on H7 for now, where we have plenty of flash
|
||||||
#if defined(STM32H7)
|
#if defined(STM32H7)
|
||||||
uavcan_protocol_debug_LogMessage pkt {};
|
uavcan_protocol_debug_LogMessage pkt {};
|
||||||
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {};
|
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
|
||||||
va_list ap;
|
va_list ap;
|
||||||
va_start(ap, fmt);
|
va_start(ap, fmt);
|
||||||
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
|
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
|
||||||
|
Loading…
Reference in New Issue
Block a user