mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
DataFlash: remove unused callbacks, unimplemented functions
Closes #3269
This commit is contained in:
parent
ca9af3ee42
commit
ff8008d81a
@ -37,9 +37,6 @@ void DFMessageWriter_DFLogStart::process()
|
|||||||
if (!_dataflash_backend->Log_Write_Format(_dataflash_backend->structure(next_format_to_send))) {
|
if (!_dataflash_backend->Log_Write_Format(_dataflash_backend->structure(next_format_to_send))) {
|
||||||
return; // call me again!
|
return; // call me again!
|
||||||
}
|
}
|
||||||
// provide hook to avoid corrupting the APM1/APM2
|
|
||||||
// dataflash by writing too fast:
|
|
||||||
_dataflash_backend->WroteStartupFormat();
|
|
||||||
next_format_to_send++;
|
next_format_to_send++;
|
||||||
}
|
}
|
||||||
_fmt_done = true;
|
_fmt_done = true;
|
||||||
@ -52,7 +49,6 @@ void DFMessageWriter_DFLogStart::process()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
ap = AP_Param::next_scalar(&token, &type);
|
ap = AP_Param::next_scalar(&token, &type);
|
||||||
_dataflash_backend->WroteStartupParam();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
stage = ls_blockwriter_stage_sysinfo;
|
stage = ls_blockwriter_stage_sysinfo;
|
||||||
|
@ -111,13 +111,6 @@ uint16_t DataFlash_Class::get_num_logs(void) {
|
|||||||
}
|
}
|
||||||
return backends[0]->get_num_logs();
|
return backends[0]->get_num_logs();
|
||||||
}
|
}
|
||||||
void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt) {
|
|
||||||
if (_next_backend == 0) {
|
|
||||||
// how were we called?!
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
backends[0]->Log_Fill_Format(s, pkt);
|
|
||||||
}
|
|
||||||
|
|
||||||
void DataFlash_Class::LogReadProcess(uint16_t log_num,
|
void DataFlash_Class::LogReadProcess(uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
@ -189,11 +182,6 @@ void DataFlash_Class::Log_Write_EntireMission(const AP_Mission &mission)
|
|||||||
FOR_EACH_BACKEND(Log_Write_EntireMission(mission));
|
FOR_EACH_BACKEND(Log_Write_EntireMission(mission));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Class::Log_Write_Format(const struct LogStructure *s)
|
|
||||||
{
|
|
||||||
FOR_EACH_BACKEND(Log_Write_Format(s));
|
|
||||||
}
|
|
||||||
|
|
||||||
void DataFlash_Class::Log_Write_Message(const char *message)
|
void DataFlash_Class::Log_Write_Message(const char *message)
|
||||||
{
|
{
|
||||||
FOR_EACH_BACKEND(Log_Write_Message(message));
|
FOR_EACH_BACKEND(Log_Write_Message(message));
|
||||||
|
@ -88,7 +88,7 @@ public:
|
|||||||
|
|
||||||
void StartNewLog(void);
|
void StartNewLog(void);
|
||||||
void EnableWrites(bool enable);
|
void EnableWrites(bool enable);
|
||||||
void Log_Write_Format(const struct LogStructure *structure);
|
|
||||||
void Log_Write_Parameter(const char *name, float value);
|
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_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
||||||
void Log_Write_RFND(const RangeFinder &rangefinder);
|
void Log_Write_RFND(const RangeFinder &rangefinder);
|
||||||
@ -149,11 +149,6 @@ public:
|
|||||||
|
|
||||||
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
|
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
|
||||||
|
|
||||||
// this is out here for the trickle-startup-messages logging.
|
|
||||||
// Think before calling.
|
|
||||||
bool Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
|
||||||
enum ap_var_type type);
|
|
||||||
|
|
||||||
vehicle_startup_message_Log_Writer _vehicle_messages;
|
vehicle_startup_message_Log_Writer _vehicle_messages;
|
||||||
|
|
||||||
// parameter support
|
// parameter support
|
||||||
@ -166,10 +161,6 @@ public:
|
|||||||
const struct LogStructure *structure(uint16_t num) const;
|
const struct LogStructure *structure(uint16_t num) const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
|
||||||
|
|
||||||
void WroteStartupFormat();
|
|
||||||
void WroteStartupParam();
|
|
||||||
|
|
||||||
const struct LogStructure *_structures;
|
const struct LogStructure *_structures;
|
||||||
uint8_t _num_types;
|
uint8_t _num_types;
|
||||||
|
@ -55,9 +55,6 @@ public:
|
|||||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||||
bool logging_started(void) const { return log_write_started; }
|
bool logging_started(void) const { return log_write_started; }
|
||||||
|
|
||||||
// initialisation this really shouldn't take structure and
|
|
||||||
// num_types, however the CLI LogReadProcess function requires it.
|
|
||||||
// That function needs to be split.
|
|
||||||
virtual void Init() {
|
virtual void Init() {
|
||||||
_writes_enabled = true;
|
_writes_enabled = true;
|
||||||
}
|
}
|
||||||
@ -86,9 +83,6 @@ public:
|
|||||||
uint8_t num_types() const;
|
uint8_t num_types() const;
|
||||||
const struct LogStructure *structure(uint8_t structure) const;
|
const struct LogStructure *structure(uint8_t structure) const;
|
||||||
|
|
||||||
virtual void WroteStartupFormat() { }
|
|
||||||
virtual void WroteStartupParam() { }
|
|
||||||
|
|
||||||
void Log_Write_EntireMission(const AP_Mission &mission);
|
void Log_Write_EntireMission(const AP_Mission &mission);
|
||||||
bool Log_Write_Format(const struct LogStructure *structure);
|
bool Log_Write_Format(const struct LogStructure *structure);
|
||||||
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
|
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
|
||||||
|
Loading…
Reference in New Issue
Block a user