DataFlash: make EnableWrites a frontend thing
This commit is contained in:
parent
b57a4e9685
commit
6a03af8f3e
@ -109,6 +109,8 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
|
|||||||
|
|
||||||
Prep();
|
Prep();
|
||||||
|
|
||||||
|
EnableWrites(true);
|
||||||
|
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Prepared log system");
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Prepared log system");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -458,10 +460,6 @@ bool DataFlash_Class::logging_started(void) {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Class::EnableWrites(bool enable) {
|
|
||||||
FOR_EACH_BACKEND(EnableWrites(enable));
|
|
||||||
}
|
|
||||||
|
|
||||||
// for DataFlash_MAVLink
|
// for DataFlash_MAVLink
|
||||||
void DataFlash_Class::remote_log_block_status_msg(mavlink_channel_t chan,
|
void DataFlash_Class::remote_log_block_status_msg(mavlink_channel_t chan,
|
||||||
mavlink_message_t* msg) {
|
mavlink_message_t* msg) {
|
||||||
|
@ -104,7 +104,8 @@ public:
|
|||||||
/* poke backends to start if they're not already started */
|
/* poke backends to start if they're not already started */
|
||||||
void StartUnstartedLogging(void);
|
void StartUnstartedLogging(void);
|
||||||
|
|
||||||
void EnableWrites(bool enable);
|
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||||
|
bool WritesEnabled() const { return _writes_enabled; }
|
||||||
|
|
||||||
void StopLogging();
|
void StopLogging();
|
||||||
|
|
||||||
@ -288,4 +289,7 @@ private:
|
|||||||
|
|
||||||
// possibly expensive calls to start log system:
|
// possibly expensive calls to start log system:
|
||||||
void Prep();
|
void Prep();
|
||||||
|
|
||||||
|
bool _writes_enabled;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -262,7 +262,7 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool
|
|||||||
|
|
||||||
bool DataFlash_Backend::WritesOK() const
|
bool DataFlash_Backend::WritesOK() const
|
||||||
{
|
{
|
||||||
if (!_writes_enabled) {
|
if (!_front.WritesEnabled()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) {
|
if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) {
|
||||||
|
@ -51,12 +51,9 @@ public:
|
|||||||
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
|
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
|
||||||
|
|
||||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
|
||||||
virtual bool logging_started(void) const { return log_write_started; }
|
virtual bool logging_started(void) const { return log_write_started; }
|
||||||
|
|
||||||
virtual void Init() {
|
virtual void Init() { }
|
||||||
_writes_enabled = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void set_mission(const AP_Mission *mission);
|
void set_mission(const AP_Mission *mission);
|
||||||
|
|
||||||
@ -142,8 +139,6 @@ protected:
|
|||||||
|
|
||||||
virtual bool WritesOK() const;
|
virtual bool WritesOK() const;
|
||||||
|
|
||||||
bool _writes_enabled = false;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read a block
|
read a block
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user