mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Copter: added a bit in LOG_BITMASK for PID logging
This commit is contained in:
parent
95ff71940c
commit
1792710f41
@ -972,10 +972,12 @@ static void ten_hz_logging_loop()
|
|||||||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
Log_Write_Rate();
|
Log_Write_Rate();
|
||||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
|
if (should_log(MASK_LOG_PID)) {
|
||||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
|
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
|
||||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
|
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
|
||||||
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.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)) {
|
if (should_log(MASK_LOG_MOTBATT)) {
|
||||||
Log_Write_MotBatt();
|
Log_Write_MotBatt();
|
||||||
@ -1004,10 +1006,12 @@ static void fifty_hz_logging_loop()
|
|||||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
Log_Write_Rate();
|
Log_Write_Rate();
|
||||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
|
if (should_log(MASK_LOG_PID)) {
|
||||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
|
DataFlash.Log_Write_PID(LOG_PIDR_MSG, g.pid_rate_roll.get_pid_info() );
|
||||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, g.pid_rate_yaw.get_pid_info() );
|
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g.pid_rate_pitch.get_pid_info() );
|
||||||
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g.pid_accel_z.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
|
// log IMU data if we're not already logging at the higher rate
|
||||||
|
@ -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_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
||||||
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
|
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_CAMERA) cliSerial->printf_P(PSTR(" CAMERA"));
|
||||||
|
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
|
||||||
}
|
}
|
||||||
|
|
||||||
cliSerial->println();
|
cliSerial->println();
|
||||||
@ -134,6 +135,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
TARG(OPTFLOW);
|
TARG(OPTFLOW);
|
||||||
TARG(COMPASS);
|
TARG(COMPASS);
|
||||||
TARG(CAMERA);
|
TARG(CAMERA);
|
||||||
|
TARG(PID);
|
||||||
#undef TARG
|
#undef TARG
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -415,7 +415,7 @@ public:
|
|||||||
|
|
||||||
AP_Int8 land_repositioning;
|
AP_Int8 land_repositioning;
|
||||||
AP_Float ekfcheck_thresh;
|
AP_Float ekfcheck_thresh;
|
||||||
AP_Int8 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// Heli
|
// Heli
|
||||||
|
@ -344,7 +344,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: LOG_BITMASK
|
// @Param: LOG_BITMASK
|
||||||
// @DisplayName: Log bitmask
|
// @DisplayName: Log bitmask
|
||||||
// @Description: 4 byte bitmap of log types to enable
|
// @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
|
// @User: Standard
|
||||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||||
|
|
||||||
|
@ -252,7 +252,7 @@ enum FlipState {
|
|||||||
#define MASK_LOG_CURRENT (1<<9)
|
#define MASK_LOG_CURRENT (1<<9)
|
||||||
#define MASK_LOG_RCOUT (1<<10)
|
#define MASK_LOG_RCOUT (1<<10)
|
||||||
#define MASK_LOG_OPTFLOW (1<<11)
|
#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_COMPASS (1<<13)
|
||||||
#define MASK_LOG_INAV (1<<14) // deprecated
|
#define MASK_LOG_INAV (1<<14) // deprecated
|
||||||
#define MASK_LOG_CAMERA (1<<15)
|
#define MASK_LOG_CAMERA (1<<15)
|
||||||
|
Loading…
Reference in New Issue
Block a user