From 4186edad3f0eb3231542f8beff0ab961c21707de Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 15 Apr 2023 00:36:19 +0100 Subject: [PATCH] AP_DroneCAN: move to hal.util->snprintf to keep g++ 7.5.0 happy --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 74cdbda088..1d7c68b0a7 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -194,7 +194,7 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) return; } - node_info_rsp.name.len = snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index); + node_info_rsp.name.len = hal.util->snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index); node_info_rsp.software_version.major = AP_DRONECAN_SW_VERS_MAJOR; node_info_rsp.software_version.minor = AP_DRONECAN_SW_VERS_MINOR; @@ -317,7 +317,7 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) canard_iface.process(1000); } - snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index); + hal.util->snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index); if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DroneCAN::loop, void), _thread_name, DRONECAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: couldn't create thread\n\r");