Plane: when logging is disabled don't include DataFlash at all

This commit is contained in:
Andrew Tridgell 2013-04-20 07:24:22 +10:00
parent 0c5b393919
commit 5c553852ed
2 changed files with 18 additions and 2 deletions

View File

@ -112,6 +112,7 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...);
////////////////////////////////////////////////////////////////////////////////
// DataFlash
////////////////////////////////////////////////////////////////////////////////
#if LOGGING_ENABLED == ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
@ -124,6 +125,7 @@ static DataFlash_File DataFlash("/fs/microsd/APM/logs");
// no dataflash driver
DataFlash_Empty DataFlash;
#endif
#endif
////////////////////////////////////////////////////////////////////////////////
// Sensors
@ -759,7 +761,7 @@ static void fast_loop()
Log_Write_Attitude();
if (g.log_bitmask & MASK_LOG_IMU)
DataFlash.Log_Write_IMU(&ins);
Log_Write_IMU();
// inertial navigation
// ------------------
@ -880,7 +882,7 @@ static void medium_loop()
Log_Write_Nav_Tuning();
if (g.log_bitmask & MASK_LOG_GPS)
DataFlash.Log_Write_GPS(g_gps, current_loc.alt);
Log_Write_GPS();
break;
// This case controls the slow loop

View File

@ -411,6 +411,16 @@ static void Log_Write_Compass()
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
static void Log_Write_GPS(void)
{
DataFlash.Log_Write_GPS(g_gps, current_loc.alt);
}
static void Log_Write_IMU()
{
DataFlash.Log_Write_IMU(&ins);
}
static const struct LogStructure log_structure[] PROGMEM = {
LOG_COMMON_STRUCTURES,
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
@ -464,6 +474,10 @@ static void Log_Write_Performance() {}
static void Log_Write_Attitude() {}
static void Log_Write_Control_Tuning() {}
static void Log_Write_Camera() {}
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Compass() {}
static void Log_Write_GPS() {}
static void Log_Write_IMU() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
return 0;