DataFlash: remove unused functions
This commit is contained in:
parent
eeb4613b0c
commit
326e68544c
@ -142,12 +142,6 @@ void DFMessageWriter_WriteSysInfo::process() {
|
|||||||
_finished = true; // all done!
|
_finished = true; // all done!
|
||||||
}
|
}
|
||||||
|
|
||||||
// void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string)
|
|
||||||
// {
|
|
||||||
// DFMessageWriter_WriteSysInfo writer(firmware_string);
|
|
||||||
// writer->process();
|
|
||||||
// }
|
|
||||||
|
|
||||||
void DFMessageWriter_WriteEntireMission::process() {
|
void DFMessageWriter_WriteEntireMission::process() {
|
||||||
switch(stage) {
|
switch(stage) {
|
||||||
|
|
||||||
|
@ -88,7 +88,6 @@ public:
|
|||||||
|
|
||||||
void StartNewLog(void);
|
void StartNewLog(void);
|
||||||
void EnableWrites(bool enable);
|
void EnableWrites(bool enable);
|
||||||
void Log_Write_SysInfo(const char *firmware_string);
|
|
||||||
void Log_Write_Format(const struct LogStructure *structure);
|
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);
|
||||||
@ -117,7 +116,6 @@ public:
|
|||||||
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
|
void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle);
|
||||||
void Log_Write_Compass(const Compass &compass);
|
void Log_Write_Compass(const Compass &compass);
|
||||||
void Log_Write_Mode(uint8_t mode);
|
void Log_Write_Mode(uint8_t mode);
|
||||||
void Log_Write_Parameters(void);
|
|
||||||
|
|
||||||
void Log_Write_EntireMission(const AP_Mission &mission);
|
void Log_Write_EntireMission(const AP_Mission &mission);
|
||||||
void Log_Write_Mission_Cmd(const AP_Mission &mission,
|
void Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||||
|
@ -702,26 +702,6 @@ bool DataFlash_Backend::Log_Write_Parameter(const AP_Param *ap,
|
|||||||
return Log_Write_Parameter(name, ap->cast_to_float(type));
|
return Log_Write_Parameter(name, ap->cast_to_float(type));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
write all parameters to the log - used when starting a new log so
|
|
||||||
the log file has a full record of the parameters
|
|
||||||
*/
|
|
||||||
void DataFlash_Class::Log_Write_Parameters(void)
|
|
||||||
{
|
|
||||||
AP_Param::ParamToken token;
|
|
||||||
AP_Param *ap;
|
|
||||||
enum ap_var_type type;
|
|
||||||
|
|
||||||
for (ap=AP_Param::first(&token, &type);
|
|
||||||
ap;
|
|
||||||
ap=AP_Param::next_scalar(&token, &type)) {
|
|
||||||
Log_Write_Parameter(ap, token, type);
|
|
||||||
// slow down the parameter dump to prevent saturating
|
|
||||||
// the dataflash write bandwidth
|
|
||||||
hal.scheduler->delay(1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write an GPS packet
|
// Write an GPS packet
|
||||||
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relative_alt)
|
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relative_alt)
|
||||||
{
|
{
|
||||||
@ -1028,24 +1008,6 @@ void DataFlash_Class::Log_Write_Vibration(const AP_InertialSensor &ins)
|
|||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string)
|
|
||||||
{
|
|
||||||
Log_Write_Message(firmware_string);
|
|
||||||
|
|
||||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
|
||||||
Log_Write_Message("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// write system identifier as well if available
|
|
||||||
char sysid[40];
|
|
||||||
if (hal.util->get_system_id(sysid)) {
|
|
||||||
Log_Write_Message(sysid);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write all current parameters
|
|
||||||
Log_Write_Parameters();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write a mission command. Total length : 36 bytes
|
// Write a mission command. Total length : 36 bytes
|
||||||
bool DataFlash_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission,
|
bool DataFlash_Backend::Log_Write_Mission_Cmd(const AP_Mission &mission,
|
||||||
const AP_Mission::Mission_Command &cmd)
|
const AP_Mission::Mission_Command &cmd)
|
||||||
|
Loading…
Reference in New Issue
Block a user