APM_Control: fixed LoggerDocumentation test

This commit is contained in:
Andrew Tridgell 2021-04-02 15:22:27 +11:00
parent 0b76a8018f
commit 70c194c358
1 changed files with 49 additions and 18 deletions

View File

@ -160,10 +160,22 @@ void AP_AutoTune::stop(void)
// @LoggerMessage: ATNP
// @Description: Plane AutoTune
// @Description: Plane AutoTune pitch
// @Vehicles: Plane
// @Field: TimeUS: Time since system startup
// @Field: State: tuning state
// @Field: Sur: control surface deflection
// @Field: Tar: target rate
// @Field: FF0: FF value single sample
// @Field: FF: FF value
// @Field: P: P value
// @Field: D: D value
// @Field: Action: action taken
// @LoggerMessage: ATNR
// @Description: Plane AutoTune roll
// @Vehicles: Plane
// @Field: TimeUS: Time since system startup
// @Field: Axis: which axis is currently being tuned
// @Field: State: tuning state
// @Field: Sur: control surface deflection
// @Field: Tar: target rate
@ -228,22 +240,41 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler)
break;
}
AP::logger().Write(
type==AUTOTUNE_ROLL?"ATNR":"ATNP",
"TimeUS,Axis,State,Sur,Tar,FF0,FF,P,D,Action",
"s--dk-----",
"F--000000-",
"QBBffffffB",
AP_HAL::micros64(),
unsigned(type),
unsigned(new_state),
actuator,
desired_rate,
FF_single,
current.FF,
current.P,
current.D,
unsigned(action));
// unfortunately the LoggerDocumentation test doesn't
// like two different log msgs in one Write call
if (type == AUTOTUNE_ROLL) {
AP::logger().Write(
"ATNR",
"TimeUS,State,Sur,Tar,FF0,FF,P,D,Action",
"s-dk-----",
"F-000000-",
"QBffffffB",
AP_HAL::micros64(),
unsigned(new_state),
actuator,
desired_rate,
FF_single,
current.FF,
current.P,
current.D,
unsigned(action));
} else {
AP::logger().Write(
"ATNP",
"TimeUS,State,Sur,Tar,FF0,FF,P,D,Action",
"s-dk-----",
"F-000000-",
"QBffffffB",
AP_HAL::micros64(),
unsigned(new_state),
actuator,
desired_rate,
FF_single,
current.FF,
current.P,
current.D,
unsigned(action));
}
if (new_state == state) {
return;