diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 4f1d8bae86..8b7b5265c9 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -659,8 +659,10 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) mavlink_set_position_target_global_int_t packet; mavlink_msg_set_position_target_global_int_decode(&msg, &packet); - // exit if vehicle is not in Guided mode or Auto-Guided mode - if ((sub.control_mode != GUIDED) && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided)) { + // exit if vehicle is not in Guided, Auto-Guided, or Depth Hold modes + if ((sub.control_mode != GUIDED) + && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided) + && !(sub.control_mode == ALT_HOLD)) { break; } @@ -675,6 +677,11 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) * bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE; */ + if (!pos_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD + sub.pos_control.set_alt_target(packet.alt*100); + break; + } + Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters if (!pos_ignore) {