mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: convert to new get_rpm() API
This commit is contained in:
parent
4f54d9b75f
commit
39fc324854
|
@ -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()
|
||||
|
|
Loading…
Reference in New Issue