mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: added slew rate and Dmod for PID_TUNING message
This commit is contained in:
parent
46287dcb00
commit
7452e9dffb
|
@ -136,7 +136,9 @@ void GCS_MAVLINK_Tracker::send_pid_tuning()
|
|||
pid_info->FF,
|
||||
pid_info->P,
|
||||
pid_info->I,
|
||||
pid_info->D);
|
||||
pid_info->D,
|
||||
pid_info->slew_rate,
|
||||
pid_info->Dmod);
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
||||
return;
|
||||
}
|
||||
|
@ -152,7 +154,9 @@ void GCS_MAVLINK_Tracker::send_pid_tuning()
|
|||
pid_info->FF,
|
||||
pid_info->P,
|
||||
pid_info->I,
|
||||
pid_info->D);
|
||||
pid_info->D,
|
||||
pid_info->slew_rate,
|
||||
pid_info->Dmod);
|
||||
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue