simulator mavlink: set vision pos/val valid

This commit is contained in:
ChristophTobler
2018-01-10 08:59:41 +01:00
committed by Lorenz Meier
parent 66c67f89e6
commit 3a52e7ee5d

View File

@@ -1130,6 +1130,11 @@ int Simulator::publish_ev_topic(mavlink_vision_position_estimate_t *ev_mavlink)
vision_position.y = ev_mavlink->y;
vision_position.z = ev_mavlink->z;
vision_position.xy_valid = true;
vision_position.z_valid = true;
vision_position.v_xy_valid = true;
vision_position.v_z_valid = true;
struct vehicle_attitude_s vision_attitude = {};
vision_attitude.timestamp = timestamp;