mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: support 3 magnetometers
This commit is contained in:
parent
5aa58d2ab5
commit
fdeedfa173
@ -461,6 +461,27 @@ static void Log_Write_Compass()
|
||||
DataFlash.WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
#endif
|
||||
#if COMPASS_MAX_INSTANCES > 2
|
||||
if (compass.get_count() > 2) {
|
||||
const Vector3f &mag3_offsets = compass.get_offsets(2);
|
||||
const Vector3f &mag3_motor_offsets = compass.get_motor_offsets(2);
|
||||
const Vector3f &mag3 = compass.get_field(2);
|
||||
struct log_Compass pkt3 = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS3_MSG),
|
||||
time_ms : millis(),
|
||||
mag_x : (int16_t)mag3.x,
|
||||
mag_y : (int16_t)mag3.y,
|
||||
mag_z : (int16_t)mag3.z,
|
||||
offset_x : (int16_t)mag3_offsets.x,
|
||||
offset_y : (int16_t)mag3_offsets.y,
|
||||
offset_z : (int16_t)mag3_offsets.z,
|
||||
motor_offset_x : (int16_t)mag3_motor_offsets.x,
|
||||
motor_offset_y : (int16_t)mag3_motor_offsets.y,
|
||||
motor_offset_z : (int16_t)mag3_motor_offsets.z
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt3, sizeof(pkt3));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -74,6 +74,7 @@ enum mode {
|
||||
#define LOG_CAMERA_MSG 0x0B // deprecated
|
||||
#define LOG_COMPASS2_MSG 0x0C
|
||||
#define LOG_STEERING_MSG 0x0D
|
||||
#define LOG_COMPASS3_MSG 0x0E
|
||||
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
#define TYPE_GROUNDSTART_MSG 0x01
|
||||
|
Loading…
Reference in New Issue
Block a user