Copter: added slew rate and Dmod for PID_TUNING message
This commit is contained in:
parent
7452e9dffb
commit
dabdf69e56
@ -254,7 +254,9 @@ void GCS_MAVLINK_Copter::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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user