Copter: added a bit in LOG_BITMASK for PID logging

This commit is contained in:
Andrew Tridgell 2015-05-27 14:32:05 +10:00
parent 95ff71940c
commit 1792710f41
5 changed files with 17 additions and 11 deletions

View File

@ -972,10 +972,12 @@ static void ten_hz_logging_loop()
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
Log_Write_Rate();
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
if (should_log(MASK_LOG_PID)) {
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
}
}
if (should_log(MASK_LOG_MOTBATT)) {
Log_Write_MotBatt();
@ -1004,10 +1006,12 @@ static void fifty_hz_logging_loop()
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
Log_Write_Rate();
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
if (should_log(MASK_LOG_PID)) {
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.get_pid_info() );
}
}
// log IMU data if we're not already logging at the higher rate

View File

@ -49,6 +49,7 @@ print_log_menu(void)
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf_P(PSTR(" CAMERA"));
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
}
cliSerial->println();
@ -134,6 +135,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
TARG(OPTFLOW);
TARG(COMPASS);
TARG(CAMERA);
TARG(PID);
#undef TARG
}

View File

@ -415,7 +415,7 @@ public:
AP_Int8 land_repositioning;
AP_Float ekfcheck_thresh;
AP_Int8 gcs_pid_mask;
AP_Int16 gcs_pid_mask;
#if FRAME_CONFIG == HELI_FRAME
// Heli

View File

@ -344,7 +344,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 4 byte bitmap of log types to enable
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131070:All+DisarmedLogging,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,0:Disabled
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131070:All+DisarmedLogging,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,All+FastIMU+PID:397310,0:Disabled
// @User: Standard
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),

View File

@ -252,7 +252,7 @@ enum FlipState {
#define MASK_LOG_CURRENT (1<<9)
#define MASK_LOG_RCOUT (1<<10)
#define MASK_LOG_OPTFLOW (1<<11)
#define MASK_LOG_PID (1<<12) // deprecated
#define MASK_LOG_PID (1<<12)
#define MASK_LOG_COMPASS (1<<13)
#define MASK_LOG_INAV (1<<14) // deprecated
#define MASK_LOG_CAMERA (1<<15)