mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
DataFlash: use AP_Mission singleton
This commit is contained in:
parent
9b561c76e2
commit
590eb86a45
@ -134,12 +134,6 @@ void DFMessageWriter_WriteSysInfo::reset()
|
||||
stage = ws_blockwriter_stage_init;
|
||||
}
|
||||
|
||||
void DFMessageWriter_DFLogStart::set_mission(const AP_Mission *mission)
|
||||
{
|
||||
_writeentiremission.set_mission(mission);
|
||||
}
|
||||
|
||||
|
||||
void DFMessageWriter_WriteSysInfo::process() {
|
||||
const AP_FWVersion &fwver = AP::fwversion();
|
||||
|
||||
@ -188,6 +182,12 @@ void DFMessageWriter_WriteSysInfo::process() {
|
||||
}
|
||||
|
||||
void DFMessageWriter_WriteEntireMission::process() {
|
||||
const AP_Mission *_mission = AP::mission();
|
||||
if (_mission == nullptr) {
|
||||
_finished = true;
|
||||
return;
|
||||
}
|
||||
|
||||
switch(stage) {
|
||||
|
||||
case em_blockwriter_stage_init:
|
||||
@ -234,9 +234,3 @@ void DFMessageWriter_WriteEntireMission::reset()
|
||||
stage = em_blockwriter_stage_init;
|
||||
_mission_number_to_send = 0;
|
||||
}
|
||||
|
||||
|
||||
void DFMessageWriter_WriteEntireMission::set_mission(const AP_Mission *mission)
|
||||
{
|
||||
_mission = mission;
|
||||
}
|
||||
|
@ -43,8 +43,6 @@ public:
|
||||
void reset() override;
|
||||
void process() override;
|
||||
|
||||
void set_mission(const AP_Mission *mission);
|
||||
|
||||
private:
|
||||
enum entire_mission_blockwriter_stage {
|
||||
em_blockwriter_stage_init,
|
||||
@ -53,7 +51,6 @@ private:
|
||||
em_blockwriter_stage_done
|
||||
};
|
||||
|
||||
const AP_Mission *_mission = nullptr;
|
||||
uint16_t _mission_number_to_send = 0;
|
||||
entire_mission_blockwriter_stage stage = em_blockwriter_stage_init;
|
||||
};
|
||||
@ -76,8 +73,6 @@ public:
|
||||
void process() override;
|
||||
bool fmt_done() { return _fmt_done; }
|
||||
|
||||
void set_mission(const AP_Mission *mission);
|
||||
|
||||
private:
|
||||
|
||||
enum log_start_blockwriter_stage {
|
||||
|
@ -514,10 +514,6 @@ void DataFlash_Class::set_vehicle_armed(const bool armed_state)
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_Class::set_mission(const AP_Mission *mission) {
|
||||
FOR_EACH_BACKEND(set_mission(mission));
|
||||
}
|
||||
|
||||
// start functions pass straight through to backend:
|
||||
void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size) {
|
||||
FOR_EACH_BACKEND(WriteBlock(pBuffer, size));
|
||||
|
@ -63,8 +63,6 @@ public:
|
||||
return _instance;
|
||||
}
|
||||
|
||||
void set_mission(const AP_Mission *mission);
|
||||
|
||||
// initialisation
|
||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||
void set_num_types(uint8_t num_types) { _num_types = num_types; }
|
||||
|
@ -83,10 +83,6 @@ void DataFlash_Backend::internal_error() {
|
||||
#endif
|
||||
}
|
||||
|
||||
void DataFlash_Backend::set_mission(const AP_Mission *mission) {
|
||||
_startup_messagewriter->set_mission(mission);
|
||||
}
|
||||
|
||||
// this method can be overridden to do extra things with your buffer.
|
||||
// for example, in DataFlash_MAVLink we may push messages into the UART.
|
||||
void DataFlash_Backend::push_log_blocks() {
|
||||
|
@ -47,8 +47,6 @@ public:
|
||||
|
||||
virtual void Init() { }
|
||||
|
||||
void set_mission(const AP_Mission *mission);
|
||||
|
||||
virtual uint32_t bufferspace_available() = 0;
|
||||
|
||||
virtual void PrepForArming() { }
|
||||
|
@ -436,7 +436,6 @@ void DataFlash_Backend::Log_Write_EntireMission(const AP_Mission &mission)
|
||||
{
|
||||
DFMessageWriter_WriteEntireMission writer;
|
||||
writer.set_dataflash_backend(this);
|
||||
writer.set_mission(&mission);
|
||||
writer.process();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user