diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 8b95a51dae..f0953a8aa2 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -135,6 +135,8 @@ void Rover::init_ardupilot() log_init(); #endif + GCS_MAVLINK::set_dataflash(&DataFlash); + // Register mavlink_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);