Browse Source

GCS_MAVLink: send optflow message even if no height estimate

c415-sdk
Randy Mackay 5 years ago
parent
commit
188fdfb1b8
  1. 9
      libraries/GCS_MAVLink/GCS_Common.cpp

9
libraries/GCS_MAVLink/GCS_Common.cpp

@ -2074,12 +2074,9 @@ void GCS_MAVLINK::send_opticalflow() @@ -2074,12 +2074,9 @@ void GCS_MAVLINK::send_opticalflow()
const Vector2f &flowRate = optflow->flowRate();
const Vector2f &bodyRate = optflow->bodyRate();
const AP_AHRS &ahrs = AP::ahrs();
float hagl = 0;
if (ahrs.have_inertial_nav()) {
if (!ahrs.get_hagl(hagl)) {
return;
}
float hagl;
if (!AP::ahrs().get_hagl(hagl)) {
hagl = 0;
}
// populate and send message

Loading…
Cancel
Save