From ea5caf258fda2380ad46473d8155b2408be257dd Mon Sep 17 00:00:00 2001 From: Kabir Mohammed Date: Thu, 16 Feb 2017 14:08:55 +0530 Subject: [PATCH] mavlink : fix vision debug stream attitude update --- src/modules/mavlink/mavlink_messages.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 1f6da8e12f41..d3f35cdb9714 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1576,7 +1576,10 @@ class MavlinkStreamVisionPositionEstimate : public MavlinkStream struct vehicle_local_position_s vpos = {}; struct vehicle_attitude_s vatt = {}; - if (_pos_sub->update(&_pos_time, &vpos) || _att_sub->update(&_att_time, &vatt)) { + bool att_updated = _att_sub->update(&_att_time, &vatt); + bool pos_updated = _pos_sub->update(&_pos_time, &vpos); + + if (pos_updated || att_updated) { mavlink_vision_position_estimate_t vmsg; vmsg.usec = vpos.timestamp; vmsg.x = vpos.x;