diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 80be93626b..b28653005b 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2206,6 +2206,8 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) _hil_local_pos.yaw = euler.psi(); _hil_local_pos.xy_global = true; _hil_local_pos.z_global = true; + _hil_local_pos.vxy_max = 0.0f; + _hil_local_pos.limit_hagl = false; if (_local_pos_pub == nullptr) { _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &_hil_local_pos);