A Few Improvements for Ship Landing

Hi everyone, I am a member of the R&D team at Marine Drone Tech, Korea. Our company operates in the fisheries domain, providing VTOL-based aerial services. Our platforms are equipped with stabilized gimbal systems and are primarily used for real-time tuna detection and maritime surveillance.

Operating in offshore environments with continuously moving vessels has made ship-based takeoff and landing a critical requirement in our operations over the past two years. With the significant contributions from the Ardupilot developes, the reliability and usability of ship landing in ArduPilot have improved considerably (refer to ArduPilot Ship Landing Documentation https://ardupilot.org/plane/docs/common-ship-landing.html.).

Nevertheless, to better support pilot operation and to address practical challenges encountered in real-world offshore missions, we have implemented several additional features to further enhance the ship landing system:

1. Ship landing can now be controlled from both the GCS and RC transmitter, instead of RC-only)

2. The last home position is displayed in Mission Planner even in case of link loss

3. Enabling SHIP_AUTO_OFS while in QSTABILIZE and QHOVER modes

4. A SLND tab was added for easier management of ship landing parameters

In the following parts, I will share some real-world images, operational experience, and explain these features in more detail.

A. Offshore Operation Images:

B. Operational Considerations

Due to wave-induced motion during system startup, disabling INS gyroscope calibration is necessary to prevent incorrect bias estimation. Therefore, the parameter INS_GYRO_CAL is set to 0.

In addition, strong electromagnetic interference from onboard radar systems and other communication equipment makes compass-based heading estimation unreliable. As a result, GPS RTK yaw is preferred as the primary heading source, with EK3_SRC1_YAW configured to 2.

Furthermore, the limited working space on the vessel, combined with continuous motion caused by waves, significantly impacts pilot operation and handling efficiency. To address this, a dedicated storage and deployment solution for the VTOL platform is essential. Minimizing the need for assembly and disassembly not only improves operational efficiency but also reduces exposure of sensitive electronic components to seawater and harsh marine conditions.

C. Added Features for Ship Landing Enhancement

1. Enabling Ship Landing Control from GCS

Problem

During offshore operations, the pilot typically remains inside the vessel cabin together with the captain and crew, operating the UAV and monitoring tuna activity through the gimbal feed. In this setup, relying solely on an RC transmitter is inconvenient. A fully GCS-based control workflow is more practical, especially during automated ship landing.

However, the current ship landing implementation primarily depends on RC input (throttle states) to control different landing phases.

Implementation

To enable GCS-based control, an additional control variable from GCS (gcs_value) was introduced and mapped to throttle state logic:

   if gcs_value == 0 then
      gcs_value = nil
   end

   if gcs_value == 3 then
      gcs_tpos = THROTTLE_HIGH
   elseif gcs_value == 2 then
      gcs_tpos = THROTTLE_MID
   elseif gcs_value == 1 then
      gcs_tpos = THROTTLE_LOW
   else
      gcs_tpos = nil
   end

This allows GCS commands to emulate RC throttle positions and drive the ship landing state machine. To ensure robustness, an RC override mechanism was also implemented using an auxiliary switch. This allows the pilot to immediately

   local sw_pos = rc_chan:get_aux_switch_pos() -- returns 0, 1, 2

   if sw_pos == 0 and rc_flag == 0 then
      gcs:send_text(MAV_SEVERITY.INFO, "SLND by Controller ")
      rc_flag = 1
   elseif sw_pos ~= 0 then
      rc_flag = 0 -- Reset rc_flag when switch is not 0
   end

Additionally, a custom plugin was developed in Mission Planner to transmit control commands directly from the GCS to the vehicle.

Video:

https://www.youtube.com/watch?v=9124Xsz0x3A

2. The last home position is displayed in Mission Planner even in case of data link loss

When the communication link is lost, the VTOL will return to the last received home position. In offshore operations, the fishing vessel is continuously moving, making it difficult for the pilot to determine the direction of the VTOL relative to the vessel and properly point the antenna.

Displaying the last home position on the map relative to the vessel is therefore very important. In some cases, the captain can navigate the vessel toward that position to wait and re-establish the connection with the VTOL before continuing the operation.

Regarding antenna pointing when the VTOL loses communication and is performing RTL due to GCS failsafe activation, we integrated the beacon and tracker into a single device. We also applied machine learning, trained on historical data extracted from .bin logs, to predict the VTOL position as it returns to the last home point. This helps improve antenna pointing accuracy during link loss scenarios.

We conducted several tests using a tracker algorithm based on the Floating Frame of Reference Formulation, and recorded videos of these tests for further development and potential use in the machine learning model.

Video:

https://youtube.com/shorts/X7UK1TTjEsg?feature=share

3. Enabling automatic offset while in QSTABILIZE and QHOVER modes.

In the current implementation, auto offset is updated in QLOITER mode

However, I think using QLOITER on a moving vessel is risky. Previously, I misunderstood the code behavior related to velocity matching and used QLOITER before takeoff to perform auto offset. This resulted in accumulated position error before arming. As a consequence, when switching to AUTO, the VTOL could suddenly surge forward or backward due to the large position error.

Therefore, relying on QLOITER for auto offset introduces potential risks, especially if the pilot forgets to switch to QSTABILIZE or QHOVER before takeoff.

To mitigate this issue, the auto offset update logic was moved earlier in the code. This allows auto offset to be calculated in QSTABILIZE and QHOVER, reducing accumulated error and improving safety during takeoff from a moving vessel.

   update_auto_offset()
   --[[
      get target location before we check vehicle state to prevent a
      race condition with the user changing mode or target
   --]]
   local next_WP = vehicle:get_target_location()
   if not next_WP then
      -- not in a flight mode with a target location
      return
   end

4. A SLND tab was added for easier management of ship landing parameters

When training new pilots or working with new partners, ship landing-related parameters are organized into a dedicated tab to improve usability and visibility.

This makes it easier to monitor and configure parameters such as SHIP_AUTO_OFS. In particular, the values of FOLL_OFS_X, Y, Z are updated and clearly displayed without requiring the user to switch to the Messages tab or scroll through parameters when setting SHIP_AUTO_OFS = 1.


Note: If any of the changes above carry potential risks, please feel free to share your thoughts. Thank you for taking the time to read this post.

9 Likes

It was nicely drafted. I enjoyed reading this post. Could you please say what kind of ship you are operating on, like what is size of the ship and what is size of the takeoff and landing area that you are using uninterruptedly. What is the maximum speed you are able to do takeoff and land? And also are you using only fixed wing or multi rotor for such operation.

Hi @d_buger, we use only VTOL due to the requirements for flight time and coverage range. The vessel is approximately 80m x 12m. The landing area is about 10x10. The ship typically operates at a speed of 5–7 m/s. The maximum speed for safe takeoff and landing depends on vtol’s wind resistance; our vtol can handle wind speeds of up to 14 m/s.

1 Like

That’s quite convenient, having the additional option to control it directly from the GCS.