Browse Source

Plane: added RCIN and SRVO logging

master
Andrew Tridgell 11 years ago
parent
commit
a05a32dbda
  1. 4
      ArduPlane/ArduPlane.pde
  2. 9
      ArduPlane/Log.pde
  3. 3
      ArduPlane/config.h
  4. 2
      ArduPlane/defines.h

4
ArduPlane/ArduPlane.pde

@ -902,8 +902,12 @@ static void update_logging(void) @@ -902,8 +902,12 @@ static void update_logging(void)
if (g.log_bitmask & MASK_LOG_NTUN)
Log_Write_Nav_Tuning();
if (g.log_bitmask & MASK_LOG_RC)
Log_Write_RC();
}
/*
check for OBC failsafe check
*/

9
ArduPlane/Log.pde

@ -51,6 +51,7 @@ print_log_menu(void) @@ -51,6 +51,7 @@ print_log_menu(void)
PLOG(COMPASS);
PLOG(TECS);
PLOG(CAMERA);
PLOG(RC);
#undef PLOG
}
@ -142,6 +143,7 @@ select_logs(uint8_t argc, const Menu::arg *argv) @@ -142,6 +143,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
TARG(COMPASS);
TARG(TECS);
TARG(CAMERA);
TARG(RC);
#undef TARG
}
@ -450,6 +452,12 @@ static void Log_Write_IMU() @@ -450,6 +452,12 @@ static void Log_Write_IMU()
DataFlash.Log_Write_IMU(ins);
}
static void Log_Write_RC(void)
{
DataFlash.Log_Write_RCIN();
DataFlash.Log_Write_SERVO();
}
static const struct LogStructure log_structure[] PROGMEM = {
LOG_COMMON_STRUCTURES,
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
@ -514,6 +522,7 @@ static void Log_Write_Mode(uint8_t mode) {} @@ -514,6 +522,7 @@ static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Compass() {}
static void Log_Write_GPS() {}
static void Log_Write_IMU() {}
static void Log_Write_RC() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
return 0;

3
ArduPlane/config.h

@ -451,7 +451,8 @@ @@ -451,7 +451,8 @@
MASK_LOG_COMPASS | \
MASK_LOG_CURRENT | \
MASK_LOG_TECS | \
MASK_LOG_CAMERA
MASK_LOG_CAMERA | \
MASK_LOG_RC

2
ArduPlane/defines.h

@ -161,6 +161,7 @@ enum log_messages { @@ -161,6 +161,7 @@ enum log_messages {
LOG_MODE_MSG,
LOG_COMPASS_MSG,
LOG_TECS_MSG,
LOG_RC_MSG,
MAX_NUM_LOGS // always at the end
};
@ -177,6 +178,7 @@ enum log_messages { @@ -177,6 +178,7 @@ enum log_messages {
#define MASK_LOG_COMPASS (1<<10)
#define MASK_LOG_TECS (1<<11)
#define MASK_LOG_CAMERA (1<<12)
#define MASK_LOG_RC (1<<13)
// Waypoint Modes
// ----------------

Loading…
Cancel
Save