AP_Logger: PID move limit to flag bit

This commit is contained in:
Iampete1 2023-09-12 20:40:07 +01:00 committed by Andrew Tridgell
parent d2549ecc68
commit 5def9e7038
2 changed files with 14 additions and 4 deletions

View File

@ -473,6 +473,15 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position,
// Write a Yaw PID packet
void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
{
enum class log_PID_Flags : uint8_t {
LIMIT = 1U<<0, // true if the output is saturated, I term anti windup is active
};
uint8_t flags = 0;
if (info.limit) {
flags |= (uint8_t)log_PID_Flags::LIMIT;
}
const struct log_PID pkt{
LOG_PACKET_HEADER_INIT(msg_type),
time_us : AP_HAL::micros64(),
@ -485,7 +494,7 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
FF : info.FF,
Dmod : info.Dmod,
slew_rate : info.slew_rate,
limit : info.limit
flags : flags
};
WriteBlock(&pkt, sizeof(pkt));
}

View File

@ -407,7 +407,7 @@ struct PACKED log_PID {
float FF;
float Dmod;
float slew_rate;
uint8_t limit;
uint8_t flags;
};
struct PACKED log_WheelEncoder {
@ -676,7 +676,7 @@ struct PACKED log_VER {
// UNIT messages define units which can be referenced by FMTU messages
// 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,Limit"
#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Flags"
#define PID_FMT "QfffffffffB"
#define PID_UNITS "s----------"
#define PID_MULTS "F----------"
@ -909,7 +909,8 @@ struct PACKED log_VER {
// @Field: FF: controller feed-forward portion of response
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
// @Field: SRate: slew rate used in slew limiter
// @Field: Limit: 1 if I term is limited due to output saturation
// @Field: Flags: bitmask of PID state flags
// @FieldBitmaskEnum: Flags: log_PID_Flags
// @LoggerMessage: PM
// @Description: autopilot system performance and general data dumping ground