Sub: make scheduler track whether it has called the delay callback
This commit is contained in:
parent
e10c23bd43
commit
133b9930a6
@ -735,7 +735,7 @@ GCS_MAVLINK_Sub::data_stream_send(void)
|
||||
return;
|
||||
}
|
||||
|
||||
if (sub.in_mavlink_delay) {
|
||||
if (hal.scheduler->in_delay_callback()) {
|
||||
// don't send any other stream types while in the delay callback
|
||||
return;
|
||||
}
|
||||
@ -1522,11 +1522,10 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
||||
void Sub::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
if (!gcs().chan(0).initialised || in_mavlink_delay) {
|
||||
if (!gcs().chan(0).initialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
|
||||
uint32_t tnow = millis();
|
||||
@ -1548,7 +1547,6 @@ void Sub::mavlink_delay_cb()
|
||||
}
|
||||
|
||||
DataFlash.EnableWrites(true);
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -52,7 +52,6 @@ Sub::Sub(void)
|
||||
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
||||
loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||
in_mavlink_delay(false),
|
||||
param_loader(var_info),
|
||||
last_pilot_yaw_input_ms(0)
|
||||
{
|
||||
|
@ -436,9 +436,6 @@ private:
|
||||
AP_Terrain terrain{ahrs, mission, rally};
|
||||
#endif
|
||||
|
||||
// use this to prevent recursion during sensor init
|
||||
bool in_mavlink_delay;
|
||||
|
||||
// Top-level logic
|
||||
// setup the var_info table
|
||||
AP_Param param_loader;
|
||||
|
Loading…
Reference in New Issue
Block a user