Browse Source

GCS_MAVLink: convert to new get_rpm() API

c415-sdk
Andrew Tridgell 5 years ago
parent
commit
39fc324854
  1. 9
      libraries/GCS_MAVLink/GCS_Common.cpp

9
libraries/GCS_MAVLink/GCS_Common.cpp

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

Loading…
Cancel
Save