mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Copter: added logging of 2nd compass
This commit is contained in:
parent
beb9bffcf2
commit
5802d7f86b
@ -368,6 +368,7 @@ static void Log_Write_Compass()
|
|||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
#if COMPASS_MAX_INSTANCES > 1
|
#if COMPASS_MAX_INSTANCES > 1
|
||||||
|
if (compass.get_count() > 1) {
|
||||||
const Vector3f &mag2_offsets = compass.get_offsets(1);
|
const Vector3f &mag2_offsets = compass.get_offsets(1);
|
||||||
const Vector3f &mag2_motor_offsets = compass.get_motor_offsets(1);
|
const Vector3f &mag2_motor_offsets = compass.get_motor_offsets(1);
|
||||||
const Vector3f &mag2 = compass.get_field(1);
|
const Vector3f &mag2 = compass.get_field(1);
|
||||||
@ -384,6 +385,7 @@ static void Log_Write_Compass()
|
|||||||
motor_offset_z : (int16_t)mag2_motor_offsets.z
|
motor_offset_z : (int16_t)mag2_motor_offsets.z
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt2, sizeof(pkt2));
|
DataFlash.WriteBlock(&pkt2, sizeof(pkt2));
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user