mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Camera: retry RunCam device info maximum number of times
This commit is contained in:
parent
d075cc3cc5
commit
de076ff259
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user