AP_Logger: added SRate logging to PIDs

This commit is contained in:
Andrew Tridgell 2021-04-04 19:49:09 +10:00
parent 772b1262d4
commit 05d5fc2ecc
3 changed files with 9 additions and 5 deletions

View File

@ -357,6 +357,7 @@ public:
float D;
float FF;
float Dmod;
float slew_rate;
bool limit;
};

View File

@ -498,6 +498,7 @@ void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
D : info.D,
FF : info.FF,
Dmod : info.Dmod,
slew_rate : info.slew_rate,
limit : info.limit
};
WriteBlock(&pkt, sizeof(pkt));

View File

@ -405,6 +405,7 @@ struct PACKED log_PID {
float D;
float FF;
float Dmod;
float slew_rate;
uint8_t limit;
};
@ -846,10 +847,10 @@ struct PACKED log_PSCZ {
#define ISBD_UNITS "s--ooo"
#define ISBD_MULTS "F--???"
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,Limit"
#define PID_FMT "QffffffffB"
#define PID_UNITS "s---------"
#define PID_MULTS "F---------"
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Limit"
#define PID_FMT "QfffffffffB"
#define PID_UNITS "s----------"
#define PID_MULTS "F----------"
// @LoggerMessage: ACC
// @Description: IMU accelerometer data
@ -1192,7 +1193,8 @@ struct PACKED log_PSCZ {
// @Field: D: derivative part of PID
// @Field: FF: controller feed-forward portion of response
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
// @Field: Limit: 1 if I term is limited due to output saturation
// @Field: SRate: slew rate used in slew limiter
// @Field: Limit: 1 if I term is limited due to output saturation
// @LoggerMessage: PM
// @Description: autopilot system performance and general data dumping ground