Browse Source

ArduCopter: use new logging method for remaining packet types

Additional changes include renaming RAW dataflash type to IMU
master
Randy Mackay 12 years ago
parent
commit
87627d883b
  1. 6
      ArduCopter/ArduCopter.pde
  2. 1241
      ArduCopter/Log.pde
  3. 6
      ArduCopter/config.h
  4. 11
      ArduCopter/defines.h
  5. 2
      ArduCopter/system.pde

6
ArduCopter/ArduCopter.pde

@ -1240,8 +1240,8 @@ static void fifty_hz_loop() @@ -1240,8 +1240,8 @@ static void fifty_hz_loop()
#endif
}
if (g.log_bitmask & MASK_LOG_RAW && motors.armed())
Log_Write_Raw();
if (g.log_bitmask & MASK_LOG_IMU && motors.armed())
Log_Write_IMU();
#endif
}
@ -1335,7 +1335,9 @@ static void slow_loop() @@ -1335,7 +1335,9 @@ static void slow_loop()
// 1Hz loop
static void super_slow_loop()
{
if (g.log_bitmask != 0) {
Log_Write_Data(DATA_AP_STATE, ap.value);
}
if (g.log_bitmask & MASK_LOG_CUR && motors.armed())
Log_Write_Current();

1241
ArduCopter/Log.pde

File diff suppressed because it is too large Load Diff

6
ArduCopter/config.h

@ -1065,8 +1065,8 @@ @@ -1065,8 +1065,8 @@
#ifndef LOG_MODE
# define LOG_MODE ENABLED
#endif
#ifndef LOG_RAW
# define LOG_RAW DISABLED
#ifndef LOG_IMU
# define LOG_IMU DISABLED
#endif
#ifndef LOG_CMD
# define LOG_CMD ENABLED
@ -1107,7 +1107,7 @@ @@ -1107,7 +1107,7 @@
LOGBIT(CTUN) | \
LOGBIT(NTUN) | \
LOGBIT(MODE) | \
LOGBIT(RAW) | \
LOGBIT(IMU) | \
LOGBIT(CMD) | \
LOGBIT(CUR) | \
LOGBIT(MOTORS) | \

11
ArduCopter/defines.h

@ -277,19 +277,24 @@ enum gcs_severity { @@ -277,19 +277,24 @@ enum gcs_severity {
#define LOG_CONTROL_TUNING_MSG 0x04
#define LOG_NAV_TUNING_MSG 0x05
#define LOG_PERFORMANCE_MSG 0x06
#define LOG_RAW_MSG 0x07
#define LOG_IMU_MSG 0x07
#define LOG_CMD_MSG 0x08
#define LOG_CURRENT_MSG 0x09
#define LOG_STARTUP_MSG 0x0A
#define LOG_MOTORS_MSG 0x0B
#define LOG_OPTFLOW_MSG 0x0C
#define LOG_DATA_MSG 0x0D
#define LOG_EVENT_MSG 0x0D
#define LOG_PID_MSG 0x0E
#define LOG_ITERM_MSG 0x0F
#define LOG_DMP_MSG 0x10
#define LOG_INAV_MSG 0x11
#define LOG_CAMERA_MSG 0x12
#define LOG_ERROR_MSG 0x13
#define LOG_DATA_INT16_MSG 0x14
#define LOG_DATA_UINT16_MSG 0x15
#define LOG_DATA_INT32_MSG 0x16
#define LOG_DATA_UINT32_MSG 0x17
#define LOG_DATA_FLOAT_MSG 0x18
#define LOG_INDEX_MSG 0xF0
#define MAX_NUM_LOGS 50
@ -300,7 +305,7 @@ enum gcs_severity { @@ -300,7 +305,7 @@ enum gcs_severity {
#define MASK_LOG_CTUN (1<<4)
#define MASK_LOG_NTUN (1<<5)
#define MASK_LOG_MODE (1<<6)
#define MASK_LOG_RAW (1<<7)
#define MASK_LOG_IMU (1<<7)
#define MASK_LOG_CMD (1<<8)
#define MASK_LOG_CUR (1<<9)
#define MASK_LOG_MOTORS (1<<10)

2
ArduCopter/system.pde

@ -571,7 +571,9 @@ static void @@ -571,7 +571,9 @@ static void
init_simple_bearing()
{
initial_simple_bearing = ahrs.yaw_sensor;
if (g.log_bitmask != 0) {
Log_Write_Data(DATA_INIT_SIMPLE_BEARING, initial_simple_bearing);
}
}
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED

Loading…
Cancel
Save