mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: don't do any GCS stuff in delay callback if we're Replay
We haven't initialised the GCS at all, so it's not a great idea to update_receive() and the like.
This commit is contained in:
parent
29d042dbc7
commit
0d396f4235
|
@ -173,6 +173,11 @@ void AP_Vehicle::get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, ui
|
|||
*/
|
||||
void AP_Vehicle::scheduler_delay_callback()
|
||||
{
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
// compass.init() delays, so we end up here.
|
||||
return;
|
||||
#endif
|
||||
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
|
||||
AP_Logger &logger = AP::logger();
|
||||
|
|
Loading…
Reference in New Issue