From 6b9854457d19452d287b6367771f295bd9191f56 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 8 Jun 2015 21:08:34 +1000 Subject: [PATCH] Plane: added PID tuning logging for ground steering --- ArduPlane/GCS_Mavlink.cpp | 17 +++++++++++++++-- ArduPlane/Log.cpp | 1 + 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 58735c0501..c15172bb0d 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -466,7 +466,7 @@ void Plane::send_pid_tuning(mavlink_channel_t chan) const Vector3f &gyro = ahrs.get_gyro(); if (g.gcs_pid_mask & 1) { const DataFlash_Class::PID_Info &pid_info = rollController.get_pid_info(); - mavlink_msg_pid_tuning_send(chan, 1, + mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL, pid_info.desired, degrees(gyro.x), pid_info.FF, @@ -479,7 +479,7 @@ void Plane::send_pid_tuning(mavlink_channel_t chan) } if (g.gcs_pid_mask & 2) { const DataFlash_Class::PID_Info &pid_info = pitchController.get_pid_info(); - mavlink_msg_pid_tuning_send(chan, 2, + mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, pid_info.desired, degrees(gyro.y), pid_info.FF, @@ -490,6 +490,19 @@ void Plane::send_pid_tuning(mavlink_channel_t chan) return; } } + if (g.gcs_pid_mask & 8) { + const DataFlash_Class::PID_Info &pid_info = steerController.get_pid_info(); + mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER, + pid_info.desired, + degrees(gyro.z), + pid_info.FF, + pid_info.P, + pid_info.I, + pid_info.D); + if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { + return; + } + } } void Plane::send_rangefinder(mavlink_channel_t chan) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 640590f42e..0150118c2b 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -171,6 +171,7 @@ void Plane::Log_Write_Attitude(void) #if HAL_CPU_CLASS > HAL_CPU_CLASS_16 DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info()); DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info()); + DataFlash.Log_Write_PID(LOG_PIDY_MSG, steerController.get_pid_info()); #endif #if AP_AHRS_NAVEKF_AVAILABLE