mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: Change Compass logging to new DataFlash method that handles instances.
This commit is contained in:
parent
80929c389e
commit
b8822a42b6
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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){}
|
||||
|
Loading…
Reference in New Issue
Block a user