mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Plane: Log the steering controller PID state
This commit is contained in:
parent
6cd81ae1fb
commit
54c06cde02
@ -492,6 +492,19 @@ void Plane::send_pid_tuning(mavlink_channel_t chan)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (g.gcs_pid_mask & 4) {
|
||||||
|
const DataFlash_Class::PID_Info &pid_info = yawController.get_pid_info();
|
||||||
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
if (g.gcs_pid_mask & 8) {
|
if (g.gcs_pid_mask & 8) {
|
||||||
const DataFlash_Class::PID_Info &pid_info = steerController.get_pid_info();
|
const DataFlash_Class::PID_Info &pid_info = steerController.get_pid_info();
|
||||||
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
|
||||||
|
@ -171,6 +171,7 @@ void Plane::Log_Write_Attitude(void)
|
|||||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
|
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_PIDP_MSG, pitchController.get_pid_info());
|
||||||
|
DataFlash.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
|
||||||
DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user