mirror of https://github.com/ArduPilot/ardupilot
Rover: pitch PID_TUNING sends degrees
also send FF although it is rarely used
This commit is contained in:
parent
db611e074c
commit
e0fa829665
|
@ -217,9 +217,9 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
|
||||||
if (g.gcs_pid_mask & 4) {
|
if (g.gcs_pid_mask & 4) {
|
||||||
pid_info = &g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info();
|
pid_info = &g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info();
|
||||||
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
|
||||||
pid_info->desired,
|
degrees(pid_info->desired),
|
||||||
ahrs.pitch,
|
degrees(ahrs.pitch),
|
||||||
0,
|
pid_info->FF,
|
||||||
pid_info->P,
|
pid_info->P,
|
||||||
pid_info->I,
|
pid_info->I,
|
||||||
pid_info->D);
|
pid_info->D);
|
||||||
|
|
Loading…
Reference in New Issue