mirror of https://github.com/ArduPilot/ardupilot
Copter: logging disentangle and correct bugs and rename bitmasks
fix
This commit is contained in:
parent
f3da373beb
commit
d3aebd72d8
|
@ -489,10 +489,14 @@ void Copter::loop_rate_logging()
|
|||
{
|
||||
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||
Log_Write_Attitude();
|
||||
Log_Write_PIDS(); // only logs if PIDS bitmask is set
|
||||
}
|
||||
if (should_log(MASK_LOG_FTN_FAST)) {
|
||||
AP::ins().write_notch_log_messages();
|
||||
}
|
||||
if (should_log(MASK_LOG_IMU_FAST)) {
|
||||
AP::ins().Write_IMU();
|
||||
}
|
||||
}
|
||||
|
||||
// ten_hz_logging_loop
|
||||
|
@ -503,8 +507,12 @@ void Copter::ten_hz_logging_loop()
|
|||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
// log EKF attitude data
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
|
||||
Log_Write_PIDS();
|
||||
}
|
||||
// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop
|
||||
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
Log_Write_EKF_POS();
|
||||
}
|
||||
if (should_log(MASK_LOG_MOTBATT)) {
|
||||
|
@ -551,7 +559,7 @@ void Copter::twentyfive_hz_logging()
|
|||
Log_Write_EKF_POS();
|
||||
}
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST))) {
|
||||
AP::ins().Write_IMU();
|
||||
}
|
||||
|
||||
|
|
|
@ -803,6 +803,7 @@ private:
|
|||
void Log_Write_Control_Tuning();
|
||||
void Log_Write_Attitude();
|
||||
void Log_Write_EKF_POS();
|
||||
void Log_Write_PIDS();
|
||||
void Log_Write_Data(LogDataID id, int32_t value);
|
||||
void Log_Write_Data(LogDataID id, uint32_t value);
|
||||
void Log_Write_Data(LogDataID id, int16_t value);
|
||||
|
|
|
@ -71,7 +71,12 @@ void Copter::Log_Write_Attitude()
|
|||
targets.z = wrap_360_cd(targets.z);
|
||||
ahrs.Write_Attitude(targets);
|
||||
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
|
||||
if (should_log(MASK_LOG_PID)) {
|
||||
}
|
||||
|
||||
// Write PIDS packets
|
||||
void Copter::Log_Write_PIDS()
|
||||
{
|
||||
if (should_log(MASK_LOG_PID)) {
|
||||
logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
|
|
|
@ -321,8 +321,8 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
|
||||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: 4 byte bitmap of log types to enable
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW,20:VideoStabilization,21:Fast harmonic notch updates
|
||||
// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535.
|
||||
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging
|
||||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
|
|
Loading…
Reference in New Issue