mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
DataFlash: StopLogging method, virtual stop_logging on backends
This commit is contained in:
parent
77dd170e03
commit
518fabe035
@ -81,6 +81,11 @@ void DataFlash_Class::Prep() {
|
||||
FOR_EACH_BACKEND(Prep());
|
||||
}
|
||||
|
||||
void DataFlash_Class::StopLogging()
|
||||
{
|
||||
FOR_EACH_BACKEND(stop_logging());
|
||||
}
|
||||
|
||||
uint16_t DataFlash_Class::find_last_log() const {
|
||||
if (_next_backend == 0) {
|
||||
return 0;
|
||||
|
@ -96,6 +96,8 @@ public:
|
||||
void StartNewLog(void);
|
||||
void EnableWrites(bool enable);
|
||||
|
||||
void StopLogging();
|
||||
|
||||
void Log_Write_Parameter(const char *name, float value);
|
||||
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
||||
void Log_Write_RFND(const RangeFinder &rangefinder);
|
||||
|
@ -65,6 +65,14 @@ public:
|
||||
virtual uint16_t start_new_log(void) = 0;
|
||||
bool log_write_started;
|
||||
|
||||
/* stop logging - close output files etc etc.
|
||||
*
|
||||
* note that this doesn't stop logging from starting up again
|
||||
* immediately - e.g. DataFlash_MAVLink might get another start
|
||||
* packet from a client.
|
||||
*/
|
||||
virtual void stop_logging(void) = 0;
|
||||
|
||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
@ -201,6 +201,14 @@ void DataFlash_MAVLink::free_all_blocks()
|
||||
_latest_block_len = 0;
|
||||
}
|
||||
|
||||
void DataFlash_MAVLink::stop_logging()
|
||||
{
|
||||
if (_sending_to_client) {
|
||||
_sending_to_client = false;
|
||||
_last_response_time = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
|
||||
void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint32_t seqno)
|
||||
@ -210,10 +218,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
|
||||
}
|
||||
if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) {
|
||||
Debug("Received stop-logging packet");
|
||||
if (_sending_to_client) {
|
||||
_sending_to_client = false;
|
||||
_last_response_time = AP_HAL::millis();
|
||||
}
|
||||
stop_logging();
|
||||
return;
|
||||
}
|
||||
if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_START) {
|
||||
|
@ -36,6 +36,8 @@ public:
|
||||
|
||||
bool logging_started() { return _logging_started; }
|
||||
|
||||
void stop_logging();
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
||||
bool is_critical) override;
|
||||
|
Loading…
Reference in New Issue
Block a user