mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Arducopter: Change compass logging to use common-vehicle DataFlash library.
This commit is contained in:
parent
12c3593bc3
commit
422970a1b1
@ -325,80 +325,19 @@ static void Log_Write_Control_Tuning()
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
struct PACKED log_Compass {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t time_ms;
|
||||
int16_t mag_x;
|
||||
int16_t mag_y;
|
||||
int16_t mag_z;
|
||||
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
|
||||
static void Log_Write_Compass()
|
||||
{
|
||||
const Vector3f &mag_offsets = compass.get_offsets(0);
|
||||
const Vector3f &mag_motor_offsets = compass.get_motor_offsets(0);
|
||||
const Vector3f &mag = compass.get_field(0);
|
||||
struct log_Compass pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_COMPASS_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
mag_x : (int16_t)mag.x,
|
||||
mag_y : (int16_t)mag.y,
|
||||
mag_z : (int16_t)mag.z,
|
||||
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));
|
||||
DataFlash.Log_Write_Compass(compass, 0);
|
||||
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
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),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
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));
|
||||
DataFlash.Log_Write_Compass(compass, 1);
|
||||
}
|
||||
#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 : hal.scheduler->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));
|
||||
DataFlash.Log_Write_Compass(compass, 2);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
@ -636,16 +575,6 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
||||
"NTUN", "Iffffffffff", "TimeMS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
|
||||
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
||||
"CTUN", "Ihhhffecchh", "TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
|
||||
{ LOG_COMPASS_MSG, sizeof(log_Compass),
|
||||
"MAG", "Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
|
||||
#if COMPASS_MAX_INSTANCES > 1
|
||||
{ LOG_COMPASS2_MSG, sizeof(log_Compass),
|
||||
"MAG2","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
|
||||
#endif
|
||||
#if COMPASS_MAX_INSTANCES > 2
|
||||
{ LOG_COMPASS3_MSG, sizeof(log_Compass),
|
||||
"MAG3","Ihhhhhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
|
||||
#endif
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "HHIhBHB", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
|
||||
{ LOG_MODE_MSG, sizeof(log_Mode),
|
||||
|
@ -226,7 +226,6 @@ enum FlipState {
|
||||
#define LOG_OPTFLOW_MSG 0x0C
|
||||
#define LOG_EVENT_MSG 0x0D
|
||||
#define LOG_PID_MSG 0x0E // deprecated
|
||||
#define LOG_COMPASS_MSG 0x0F
|
||||
#define LOG_INAV_MSG 0x11 // deprecated
|
||||
#define LOG_CAMERA_MSG_DEPRECATED 0x12 // deprecated
|
||||
#define LOG_ERROR_MSG 0x13
|
||||
@ -237,8 +236,6 @@ enum FlipState {
|
||||
#define LOG_DATA_FLOAT_MSG 0x18
|
||||
#define LOG_AUTOTUNE_MSG 0x19
|
||||
#define LOG_AUTOTUNEDETAILS_MSG 0x1A
|
||||
#define LOG_COMPASS2_MSG 0x1B
|
||||
#define LOG_COMPASS3_MSG 0x1C
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
#define MASK_LOG_ATTITUDE_MED (1<<1)
|
||||
|
Loading…
Reference in New Issue
Block a user