GCS_MAVLink: convert to new get_rpm() API

This commit is contained in:
Andrew Tridgell 2020-03-06 10:50:52 +11:00
parent 4f54d9b75f
commit 39fc324854
1 changed files with 7 additions and 2 deletions

View File

@ -4200,10 +4200,15 @@ void GCS_MAVLINK::send_rpm() const
return;
}
float rpm1 = -1, rpm2 = -1;
rpm->get_rpm(0, rpm1);
rpm->get_rpm(1, rpm2);
mavlink_msg_rpm_send(
chan,
rpm->get_rpm(0),
rpm->get_rpm(1));
rpm1,
rpm2);
}
void GCS_MAVLINK::send_sys_status()