mirror of https://github.com/ArduPilot/ardupilot
Rover: added slew rate and Dmod for PID_TUNING message
This commit is contained in:
parent
4c1700d195
commit
27ff63b865
|
@ -196,7 +196,9 @@ void GCS_MAVLINK_Rover::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;
|
||||
}
|
||||
|
@ -211,7 +213,9 @@ void GCS_MAVLINK_Rover::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;
|
||||
}
|
||||
|
@ -226,7 +230,9 @@ void GCS_MAVLINK_Rover::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;
|
||||
}
|
||||
|
@ -241,7 +247,9 @@ void GCS_MAVLINK_Rover::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;
|
||||
}
|
||||
|
@ -256,7 +264,9 @@ void GCS_MAVLINK_Rover::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;
|
||||
}
|
||||
|
@ -271,7 +281,9 @@ void GCS_MAVLINK_Rover::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