AP_DroneCAN: move to hal.util->snprintf to keep g++ 7.5.0 happy

This commit is contained in:
Iampete1 2023-04-15 00:36:19 +01:00 committed by Peter Hall
parent 14d2318859
commit 4186edad3f

View File

@ -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");