diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp index 45be963c3d..749ef0e2b8 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp @@ -633,9 +633,13 @@ void AP_UAVCAN_DNA_Server::handleAllocation(uint8_t driver_index, uint8_t node_i } if (rcvd_unique_id_offset) { - debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", uavcan::SystemClock::instance().getMonotonic().toUSec()/1000, (now - last_alloc_msg_ms)); + debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", + long(uavcan::SystemClock::instance().getMonotonic().toUSec()/1000), + unsigned((now - last_alloc_msg_ms))); } else { - debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", uavcan::SystemClock::instance().getMonotonic().toUSec()/1000, (now - last_alloc_msg_ms)); + debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", + long(uavcan::SystemClock::instance().getMonotonic().toUSec()/1000), + unsigned((now - last_alloc_msg_ms))); } last_alloc_msg_ms = now; diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp index e462a2e3fd..56c1cdfccd 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp @@ -166,7 +166,7 @@ bool CanIfaceMgr::add_interface(AP_HAL::CANIface *can_iface) AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Setting event handle failed\n"); return false; } - AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "UAVCANIfaceMgr: Successfully added interface %d\n"); + AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "UAVCANIfaceMgr: Successfully added interface %d\n", int(num_ifaces)); num_ifaces++; return true; }