VTOL hover during precision landing when target distance is > PLND_XY_DIST_MAX

Hi,

I’m working on precision landing on ArduPlane 4.5.5 in companion mode and observed following 2 issues:

  1. When PLAND_XY_DIST_MAX is set to 0, aircraft started hovering after detecting the target.

Found out that, in plane_precland.lua script, condition check for value 0 was missing.

   if xy_dist > PLND_XY_DIST_MAX:get() then
      -- pause descent till we are within the given radius
      vehicle:set_land_descent_rate(0)
   end

I’ve modified the script as below and then precision landing worked as expected

   if PLND_XY_DIST_MAX:get() > 0 and xy_dist > PLND_XY_DIST_MAX:get() then
      -- pause descent till we are within the given radius
      vehicle:set_land_descent_rate(0)
   end
  1. When the aircraft is taking off from higher terrain elevation and landing at lower terrain elevation and during descend phase, poscontrol state switches to QPOS_LAND_FINAL immediately after landing starts. This is because I’ve used Relative frame for my VTOL land mission command and this I’ve expected.
    But, when I enable precision landing with PLAND_XY_DIST_MAX is set to non zero value, and if my aircraft is away from the target with the distance more than the PLAND_XY_DIST_MAX, aircraft doesn’t correct it position and instead starts to hover indefinitely.
    If the target is detected within PLND_XY_DIST_MAX or if it is set to zero, then aircraft lands correctly using precision landing.
    In the below graph, PLND_XY_DIST_MAX was set to 2.5 and target distance was around 3.5m.

At this point, i’m not sure the 2nd issue I’m facing is a bug or the limitation of the precision landing.

I was wrong. My aircraft was landing correctly because the co-ordinates were correct.

When poscontrol state switches to QPOS_LAND_FINAL, precision landing doesn’t work beyond this.

Hey there,

I’m trying to implement exactly the same and I’m having some doubts and hopefully you can help me out:

  1. Since it’s a quadplane, we need to use the lua script correct?
  2. Comparing the copter and plane code, it seems like the copter makes more use of the precision landing in some modules, like in the mode.cpp file. I’m not confiddent that I will get a good result using the quadplane.

FYI, I have managed to test precision mode using the “companion” type and I can see the correct mavlink messages, but the quadplane doesn’t seem to be acting on it. It just lands normally. I’ve tested this without the lua script though.

  1. Since it’s a quadplane, we need to use the lua script correct?

Yes. You need to load this lua script and configure PLND params.

  1. Comparing the copter and plane code, it seems like the copter makes more use of the precision landing in some modules, like in the mode.cpp file. I’m not confiddent that I will get a good result using the quadplane.

Yes ArduPlane’s precision landing is not matured compared to Copter. But it works sufficient to do its safe precise landings.