mirror of https://github.com/ArduPilot/ardupilot
Copter: fix compiler warning from pid_tuning_send call
This commit is contained in:
parent
43b1694c76
commit
af8b9e703c
|
@ -426,10 +426,10 @@ void Copter::send_pid_tuning(mavlink_channel_t chan)
|
||||||
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
|
||||||
pid_info.desired*0.01f,
|
pid_info.desired*0.01f,
|
||||||
degrees(gyro.x),
|
degrees(gyro.x),
|
||||||
pid_info.FF*0.01,
|
pid_info.FF*0.01f,
|
||||||
pid_info.P*0.01,
|
pid_info.P*0.01f,
|
||||||
pid_info.I*0.01,
|
pid_info.I*0.01f,
|
||||||
pid_info.D*0.01);
|
pid_info.D*0.01f);
|
||||||
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue