mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: add PIDInfo.DFF logging
This commit is contained in:
parent
942be4f2f8
commit
5d53485be0
|
@ -496,6 +496,7 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
|
||||||
I : info.I,
|
I : info.I,
|
||||||
D : info.D,
|
D : info.D,
|
||||||
FF : info.FF,
|
FF : info.FF,
|
||||||
|
DFF : info.DFF,
|
||||||
Dmod : info.Dmod,
|
Dmod : info.Dmod,
|
||||||
slew_rate : info.slew_rate,
|
slew_rate : info.slew_rate,
|
||||||
flags : flags
|
flags : flags
|
||||||
|
|
|
@ -405,6 +405,7 @@ struct PACKED log_PID {
|
||||||
float I;
|
float I;
|
||||||
float D;
|
float D;
|
||||||
float FF;
|
float FF;
|
||||||
|
float DFF;
|
||||||
float Dmod;
|
float Dmod;
|
||||||
float slew_rate;
|
float slew_rate;
|
||||||
uint8_t flags;
|
uint8_t flags;
|
||||||
|
@ -679,10 +680,10 @@ struct PACKED log_VER {
|
||||||
// UNIT messages define units which can be referenced by FMTU messages
|
// UNIT messages define units which can be referenced by FMTU messages
|
||||||
// FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields
|
// FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields
|
||||||
|
|
||||||
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Flags"
|
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,DFF,Dmod,SRate,Flags"
|
||||||
#define PID_FMT "QfffffffffB"
|
#define PID_FMT "QffffffffffB"
|
||||||
#define PID_UNITS "s----------"
|
#define PID_UNITS "s-----------"
|
||||||
#define PID_MULTS "F----------"
|
#define PID_MULTS "F-----------"
|
||||||
|
|
||||||
#define PIDx_FMT "Qffffffff"
|
#define PIDx_FMT "Qffffffff"
|
||||||
#define PIDx_UNITS "smmnnnooo"
|
#define PIDx_UNITS "smmnnnooo"
|
||||||
|
@ -910,6 +911,7 @@ struct PACKED log_VER {
|
||||||
// @Field: I: integral part of PID
|
// @Field: I: integral part of PID
|
||||||
// @Field: D: derivative part of PID
|
// @Field: D: derivative part of PID
|
||||||
// @Field: FF: controller feed-forward portion of response
|
// @Field: FF: controller feed-forward portion of response
|
||||||
|
// @Field: DFF: controller derivative feed-forward portion of response
|
||||||
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
|
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
|
||||||
// @Field: SRate: slew rate used in slew limiter
|
// @Field: SRate: slew rate used in slew limiter
|
||||||
// @Field: Flags: bitmask of PID state flags
|
// @Field: Flags: bitmask of PID state flags
|
||||||
|
|
Loading…
Reference in New Issue