Copter: Change Compass logging to new DataFlash method that handles instances.

This commit is contained in:
Robert Lefebvre 2015-01-16 17:27:37 -05:00 committed by Randy Mackay
parent 80929c389e
commit b8822a42b6
2 changed files with 1 additions and 19 deletions

View File

@ -1046,7 +1046,7 @@ static void update_batt_compass(void)
compass.read();
// log compass information
if (should_log(MASK_LOG_COMPASS)) {
Log_Write_Compass();
DataFlash.Log_Write_Compass(compass);
}
}

View File

@ -325,23 +325,6 @@ static void Log_Write_Control_Tuning()
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
// Write a Compass packet
static void Log_Write_Compass()
{
DataFlash.Log_Write_Compass(compass, 0);
#if COMPASS_MAX_INSTANCES > 1
if (compass.get_count() > 1) {
DataFlash.Log_Write_Compass(compass, 1);
}
#endif
#if COMPASS_MAX_INSTANCES > 2
if (compass.get_count() > 2) {
DataFlash.Log_Write_Compass(compass, 2);
}
#endif
}
struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint16_t num_long_running;
@ -634,7 +617,6 @@ static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_min,
static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds) {}
#endif
static void Log_Write_Current() {}
static void Log_Write_Compass() {}
static void Log_Write_Attitude() {}
static void Log_Write_Data(uint8_t id, int16_t value){}
static void Log_Write_Data(uint8_t id, uint16_t value){}