Copter: added logging of 2nd compass
This commit is contained in:
parent
beb9bffcf2
commit
5802d7f86b
@ -368,22 +368,24 @@ static void Log_Write_Compass()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
const Vector3f &mag2_offsets = compass.get_offsets(1);
|
||||
const Vector3f &mag2_motor_offsets = compass.get_motor_offsets(1);
|
||||
const Vector3f &mag2 = compass.get_field(1);
|
||||
struct log_Compass pkt2 = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS2_MSG),
|
||||
mag_x : (int16_t)mag2.x,
|
||||
mag_y : (int16_t)mag2.y,
|
||||
mag_z : (int16_t)mag2.z,
|
||||
offset_x : (int16_t)mag2_offsets.x,
|
||||
offset_y : (int16_t)mag2_offsets.y,
|
||||
offset_z : (int16_t)mag2_offsets.z,
|
||||
motor_offset_x : (int16_t)mag2_motor_offsets.x,
|
||||
motor_offset_y : (int16_t)mag2_motor_offsets.y,
|
||||
motor_offset_z : (int16_t)mag2_motor_offsets.z
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt2, sizeof(pkt2));
|
||||
if (compass.get_count() > 1) {
|
||||
const Vector3f &mag2_offsets = compass.get_offsets(1);
|
||||
const Vector3f &mag2_motor_offsets = compass.get_motor_offsets(1);
|
||||
const Vector3f &mag2 = compass.get_field(1);
|
||||
struct log_Compass pkt2 = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS2_MSG),
|
||||
mag_x : (int16_t)mag2.x,
|
||||
mag_y : (int16_t)mag2.y,
|
||||
mag_z : (int16_t)mag2.z,
|
||||
offset_x : (int16_t)mag2_offsets.x,
|
||||
offset_y : (int16_t)mag2_offsets.y,
|
||||
offset_z : (int16_t)mag2_offsets.z,
|
||||
motor_offset_x : (int16_t)mag2_motor_offsets.x,
|
||||
motor_offset_y : (int16_t)mag2_motor_offsets.y,
|
||||
motor_offset_z : (int16_t)mag2_motor_offsets.z
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user