From de076ff2597315bddc0339ccf259a6609bccc8c8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 19 Nov 2022 17:33:50 +0000 Subject: [PATCH] AP_Camera: retry RunCam device info maximum number of times --- libraries/AP_Camera/AP_RunCam.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 4cf05fe956..4fffafbdd3 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -800,7 +800,7 @@ void AP_RunCam::start_uart() void AP_RunCam::get_device_info() { send_request_and_waiting_response(Command::RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 0, RUNCAM_INIT_INTERVAL_MS * 4, - -1, FUNCTOR_BIND_MEMBER(&AP_RunCam::parse_device_info, void, const Request&)); + UINT16_MAX, FUNCTOR_BIND_MEMBER(&AP_RunCam::parse_device_info, void, const Request&)); } // map a Event to a SimulationOperation