From 72b51a389c1300f0f0688661516d8ac14a67d1f3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 12 Apr 2021 14:43:34 +1000 Subject: [PATCH] APM_Control: use ATRP log msg via structure --- libraries/APM_Control/AP_AutoTune.cpp | 59 ++++++++------------------- libraries/APM_Control/AP_AutoTune.h | 19 ++++++--- 2 files changed, 31 insertions(+), 47 deletions(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index d4729ad566..67324ea307 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -160,25 +160,6 @@ void AP_AutoTune::stop(void) } } - -// @LoggerMessage: ATRP -// @Description: Plane AutoTune -// @Vehicles: Plane -// @Field: TimeUS: Time since system startup -// @Field: Axis: tuning axis -// @Field: State: tuning state -// @Field: Sur: control surface deflection -// @Field: Tar: target rate -// @Field: Act: actual rate -// @Field: FF0: FF value single sample -// @Field: FF: FF value -// @Field: P: P value -// @Field: I: I value -// @Field: D: D value -// @Field: Action: action taken -// @Field: RMAX: Rate maximum -// @Field: TAU: time constant - /* one update cycle of the autotuner */ @@ -242,28 +223,24 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler) break; } - // unfortunately the LoggerDocumentation test doesn't - // like two different log msgs in one Write call - AP::logger().Write( - "ATRP", - "TimeUS,Axis,State,Sur,Tar,Act,FF0,FF,P,I,D,Action,RMAX,TAU", - "s#-dkk------ks", - "F--00000000-00", - "QBBffffffffBHf", - AP_HAL::micros64(), - unsigned(type), - unsigned(new_state), - actuator, - desired_rate, - actual_rate, - FF_single, - current.FF, - current.P, - current.I, - current.D, - unsigned(action), - current.rmax_pos.get(), - current.tau); + struct log_ATRP pkt = { + LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG), + time_us : AP_HAL::micros64(), + type : uint8_t(type), + state: uint8_t(new_state), + actuator : actuator, + desired_rate : desired_rate, + actual_rate : actual_rate, + FF0: FF_single, + FF: current.FF, + P: current.P, + I: current.I, + D: current.D, + action: uint8_t(action), + rmax: float(current.rmax_pos.get()), + tau: current.tau + }; + AP::logger().WriteBlock(&pkt, sizeof(pkt)); const uint32_t now = AP_HAL::millis(); diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index a106f30722..0ca8eaefe5 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -23,12 +23,19 @@ public: struct PACKED log_ATRP { LOG_PACKET_HEADER; uint64_t time_us; - uint8_t type; - uint8_t state; - int16_t servo; - float demanded; - float achieved; - float P; + uint8_t type; + uint8_t state; + float actuator; + float desired_rate; + float actual_rate; + float FF0; + float FF; + float P; + float I; + float D; + uint8_t action; + float rmax; + float tau; };