mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: send optflow message even if no height estimate
This commit is contained in:
parent
32603b45fa
commit
188fdfb1b8
|
@ -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…
Reference in New Issue