mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Copter: Compass log stores/retrieves motor offsets
This commit is contained in:
parent
d8515ff85e
commit
6b2b69535f
@ -588,12 +588,16 @@ struct log_Compass {
|
||||
int16_t offset_x;
|
||||
int16_t offset_y;
|
||||
int16_t offset_z;
|
||||
int16_t motor_offset_x;
|
||||
int16_t motor_offset_y;
|
||||
int16_t motor_offset_z;
|
||||
};
|
||||
|
||||
// Write a Compass packet. Total length : 15 bytes
|
||||
static void Log_Write_Compass()
|
||||
{
|
||||
Vector3f mag_offsets = compass.get_offsets();
|
||||
Vector3f mag_motor_offsets = compass.get_motor_offsets();
|
||||
struct log_Compass pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG),
|
||||
mag_x : compass.mag_x,
|
||||
@ -602,6 +606,9 @@ static void Log_Write_Compass()
|
||||
offset_x : (int16_t)mag_offsets.x,
|
||||
offset_y : (int16_t)mag_offsets.y,
|
||||
offset_z : (int16_t)mag_offsets.z,
|
||||
motor_offset_x : (int16_t)mag_motor_offsets.x,
|
||||
motor_offset_y : (int16_t)mag_motor_offsets.y,
|
||||
motor_offset_z : (int16_t)mag_motor_offsets.z
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -611,14 +618,17 @@ static void Log_Read_Compass()
|
||||
{
|
||||
struct log_Compass pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
// 1 2 3 4 5 6
|
||||
cliSerial->printf_P(PSTR("COMPASS, %d, %d, %d, %d, %d, %d\n"),
|
||||
// 1 2 3 4 5 6 7 8 9
|
||||
cliSerial->printf_P(PSTR("COMPASS, %d, %d, %d, %d, %d, %d, %d, %d, %d\n"),
|
||||
(int)pkt.mag_x,
|
||||
(int)pkt.mag_y,
|
||||
(int)pkt.mag_z,
|
||||
(int)pkt.offset_x,
|
||||
(int)pkt.offset_y,
|
||||
(int)pkt.offset_z);
|
||||
(int)pkt.offset_z,
|
||||
(int)pkt.motor_offset_x,
|
||||
(int)pkt.motor_offset_y,
|
||||
(int)pkt.motor_offset_z);
|
||||
}
|
||||
|
||||
struct log_Performance {
|
||||
|
Loading…
Reference in New Issue
Block a user