mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Plane: handle knowledge of in_log_download in DataFlash
This commit is contained in:
parent
8b57405143
commit
5b70b688cb
@ -1903,23 +1903,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
||||
plane.in_log_download = true;
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_ERASE:
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
||||
if (!plane.in_mavlink_delay) {
|
||||
plane.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
||||
plane.in_log_download = false;
|
||||
if (!plane.in_mavlink_delay) {
|
||||
plane.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||
handle_serial_control(msg, plane.gps);
|
||||
break;
|
||||
|
@ -183,9 +183,6 @@ private:
|
||||
|
||||
DataFlash_Class DataFlash;
|
||||
|
||||
// has a log download started?
|
||||
bool in_log_download;
|
||||
|
||||
// scaled roll limit based on pitch
|
||||
int32_t roll_limit_cd;
|
||||
int32_t pitch_limit_min_cd;
|
||||
|
@ -841,9 +841,6 @@ bool Plane::should_log(uint32_t mask)
|
||||
if (!DataFlash.should_log()) {
|
||||
return false;
|
||||
}
|
||||
if (in_log_download) {
|
||||
return false;
|
||||
}
|
||||
start_logging();
|
||||
return true;
|
||||
#else
|
||||
|
Loading…
Reference in New Issue
Block a user