mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: added compass logging
This commit is contained in:
parent
7717cc1450
commit
0c5b393919
@ -814,6 +814,9 @@ static void medium_loop()
|
|||||||
if (g.compass_enabled && compass.read()) {
|
if (g.compass_enabled && compass.read()) {
|
||||||
ahrs.set_compass(&compass);
|
ahrs.set_compass(&compass);
|
||||||
compass.null_offsets();
|
compass.null_offsets();
|
||||||
|
if (g.log_bitmask & MASK_LOG_COMPASS) {
|
||||||
|
Log_Write_Compass();
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
ahrs.set_compass(NULL);
|
ahrs.set_compass(NULL);
|
||||||
}
|
}
|
||||||
|
@ -48,6 +48,7 @@ print_log_menu(void)
|
|||||||
PLOG(IMU);
|
PLOG(IMU);
|
||||||
PLOG(CMD);
|
PLOG(CMD);
|
||||||
PLOG(CURRENT);
|
PLOG(CURRENT);
|
||||||
|
PLOG(COMPASS);
|
||||||
#undef PLOG
|
#undef PLOG
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -136,6 +137,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
TARG(IMU);
|
TARG(IMU);
|
||||||
TARG(CMD);
|
TARG(CMD);
|
||||||
TARG(CURRENT);
|
TARG(CURRENT);
|
||||||
|
TARG(COMPASS);
|
||||||
#undef TARG
|
#undef TARG
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -375,6 +377,40 @@ static void Log_Write_Current()
|
|||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
struct PACKED log_Compass {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
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. 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,
|
||||||
|
mag_y : compass.mag_y,
|
||||||
|
mag_z : compass.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));
|
||||||
|
}
|
||||||
|
|
||||||
static const struct LogStructure log_structure[] PROGMEM = {
|
static const struct LogStructure log_structure[] PROGMEM = {
|
||||||
LOG_COMMON_STRUCTURES,
|
LOG_COMMON_STRUCTURES,
|
||||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
||||||
|
@ -714,52 +714,14 @@
|
|||||||
# define LOGGING_ENABLED ENABLED
|
# define LOGGING_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifndef LOG_ATTITUDE_FAST
|
|
||||||
# define LOG_ATTITUDE_FAST DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_ATTITUDE_MED
|
|
||||||
# define LOG_ATTITUDE_MED ENABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_GPS
|
|
||||||
# define LOG_GPS ENABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_PM
|
|
||||||
# define LOG_PM ENABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_CTUN
|
|
||||||
# define LOG_CTUN DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_NTUN
|
|
||||||
# define LOG_NTUN DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_MODE
|
|
||||||
# define LOG_MODE ENABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_IMU
|
|
||||||
# define LOG_IMU DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_CMD
|
|
||||||
# define LOG_CMD ENABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOG_CURRENT
|
|
||||||
# define LOG_CURRENT DISABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// calculate the default log_bitmask
|
|
||||||
#define LOGBIT(_s) (LOG_ ## _s ? MASK_LOG_ ## _s : 0)
|
|
||||||
|
|
||||||
#define DEFAULT_LOG_BITMASK \
|
#define DEFAULT_LOG_BITMASK \
|
||||||
LOGBIT(ATTITUDE_FAST) | \
|
MASK_LOG_ATTITUDE_MED | \
|
||||||
LOGBIT(ATTITUDE_MED) | \
|
MASK_LOG_GPS | \
|
||||||
LOGBIT(GPS) | \
|
MASK_LOG_PM | \
|
||||||
LOGBIT(PM) | \
|
MASK_LOG_NTUN | \
|
||||||
LOGBIT(CTUN) | \
|
MASK_LOG_MODE | \
|
||||||
LOGBIT(NTUN) | \
|
MASK_LOG_CMD | \
|
||||||
LOGBIT(MODE) | \
|
MASK_LOG_COMPASS
|
||||||
LOGBIT(IMU) | \
|
|
||||||
LOGBIT(CMD) | \
|
|
||||||
LOGBIT(CURRENT)
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -169,6 +169,7 @@ enum log_messages {
|
|||||||
LOG_CAMERA_MSG,
|
LOG_CAMERA_MSG,
|
||||||
LOG_ATTITUDE_MSG,
|
LOG_ATTITUDE_MSG,
|
||||||
LOG_MODE_MSG,
|
LOG_MODE_MSG,
|
||||||
|
LOG_COMPASS_MSG,
|
||||||
MAX_NUM_LOGS
|
MAX_NUM_LOGS
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -182,6 +183,7 @@ enum log_messages {
|
|||||||
#define MASK_LOG_IMU (1<<7)
|
#define MASK_LOG_IMU (1<<7)
|
||||||
#define MASK_LOG_CMD (1<<8)
|
#define MASK_LOG_CMD (1<<8)
|
||||||
#define MASK_LOG_CURRENT (1<<9)
|
#define MASK_LOG_CURRENT (1<<9)
|
||||||
|
#define MASK_LOG_COMPASS (1<<10)
|
||||||
|
|
||||||
// Waypoint Modes
|
// Waypoint Modes
|
||||||
// ----------------
|
// ----------------
|
||||||
|
Loading…
Reference in New Issue
Block a user