mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: handle knowledge of in_log_download in DataFlash
This commit is contained in:
parent
c5df219a02
commit
8b57405143
@ -182,9 +182,6 @@ private:
|
||||
// used to detect MAVLink acks from GCS to stop compassmot
|
||||
uint8_t command_ack_counter;
|
||||
|
||||
// has a log download started?
|
||||
bool in_log_download;
|
||||
|
||||
// primary input control channels
|
||||
RC_Channel *channel_roll;
|
||||
RC_Channel *channel_pitch;
|
||||
|
@ -1837,23 +1837,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
||||
copter.in_log_download = true;
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_ERASE:
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
||||
if (!copter.in_mavlink_delay && !copter.motors->armed()) {
|
||||
copter.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
||||
copter.in_log_download = false;
|
||||
if (!copter.in_mavlink_delay && !copter.motors->armed()) {
|
||||
copter.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||
handle_serial_control(msg, copter.gps);
|
||||
break;
|
||||
|
@ -922,7 +922,7 @@ void Copter::start_logging()
|
||||
if (g.log_bitmask == 0) {
|
||||
return;
|
||||
}
|
||||
if (in_log_download) {
|
||||
if (DataFlash.in_log_download()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -497,9 +497,6 @@ bool Copter::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