Skip to content

Commit

Permalink
mavlink : fix vision debug stream attitude update
Browse files Browse the repository at this point in the history
  • Loading branch information
mhkabir authored and LorenzMeier committed Feb 16, 2017
1 parent 47411b0 commit ea5caf2
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit ea5caf2

Please sign in to comment.