mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: handle knowledge of in_log_download in DataFlash
This commit is contained in:
parent
f3a717f3c0
commit
3a85d8ed39
@ -1513,23 +1513,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
||||
rover.in_log_download = true;
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_ERASE:
|
||||
/* no break */
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
||||
if (!rover.in_mavlink_delay) {
|
||||
rover.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
||||
rover.in_log_download = false;
|
||||
if (!rover.in_mavlink_delay) {
|
||||
rover.DataFlash.handle_mavlink_msg(*this, msg);
|
||||
}
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||
handle_serial_control(msg, rover.gps);
|
||||
break;
|
||||
|
@ -25,7 +25,6 @@ Rover::Rover(void) :
|
||||
channel_throttle(nullptr),
|
||||
channel_learn(nullptr),
|
||||
DataFlash{FIRMWARE_STRING},
|
||||
in_log_download(false),
|
||||
modes(&g.mode1),
|
||||
L1_controller(ahrs, nullptr),
|
||||
nav_controller(&L1_controller),
|
||||
|
@ -136,8 +136,6 @@ private:
|
||||
|
||||
DataFlash_Class DataFlash;
|
||||
|
||||
bool in_log_download;
|
||||
|
||||
// sensor drivers
|
||||
AP_GPS gps;
|
||||
AP_Baro barometer;
|
||||
|
@ -505,9 +505,6 @@ bool Rover::should_log(uint32_t mask)
|
||||
if (!DataFlash.should_log()) {
|
||||
return false;
|
||||
}
|
||||
if (in_log_download) {
|
||||
return false;
|
||||
}
|
||||
start_logging();
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user