Setting LAND waypoint via LUA script?

Hi,

how can I write a waypoint LAND into a mission via LUA script when flying over an area?

I have written a script for this myself as a test:

-- save waypoint for landing

local scripting_rc_1 = rc:find_channel_for_option(300)

local WAYPOINT    = 16
local LAND        = 21


function save_land_wp()

    local wp       = mission:get_item(0)  
	
	local instance = gps:primary_sensor()
	local position = gps:location(instance)
    -- local position = ahrs:get_position()

    if (not wp) then
		gcs:send_text(0, "no homepoint set!")
        return false
    end
    
    if (not position) then
		gcs:send_text(0, "no position data!")
        return false
    end
	
	-- gcs:send_text(0, mission:num_commands())
    
    wp:command(LAND)
    wp:x(position:lat())
    wp:y(position:lng())
    wp:z(0)  

    -- mission:set_item(mission:num_commands(), wp)
    mission:set_item(1, wp)

    return true
end


function update()

  -- read switch input from designated scripting RCx_OPTION
  if scripting_rc_1 then
  
	local sw_pos = scripting_rc_1:get_aux_switch_pos()
	
	-- gcs:send_text(0, "Save_Land_WP.lua")
 
	if sw_pos == 0 then 
      -- gcs:send_text(0, "Scripting switch is low")
    elseif sw_pos == 1 then
      -- gcs:send_text(0, "Scripting switch is middle")
    else
      -- gcs:send_text(0, "Scripting switch is high")

	  -- clear mission
	  mission:clear()

	  -- save LAND waypoint to mission
	  if save_land_wp() then 
		gcs:send_text(0, "LAND wp saved!")
	   end

    end
	
  end

  return update, 1000 -- reschedules the loop

end

return update()

This also works almost as desired. What I still don’t understand: when mission:clear() is executed, wp is not valid. With mission:get_item(0) only a template for the creation of a waypoint is created, that should always work?

Maybe @Yuri_Rage can help here?

1 Like

I had a similar issue with trying to use the home waypoint in that manner when no mission exists. Try this instead:

wp = mavlink_mission_item_int_t()

It’s a more direct way to create a “template” than using the home waypoint as some examples do.

This seems like an odd use of Lua, but you did say it’s a test script. If your intent is to just land at present position, instead of scripting a land waypoint with the flick of a switch, you could command the LAND flight mode with the same switch and skip the script altogether. Alternatively, your script could detect mission.MISSION_COMPLETE and command a switch to the LAND flight mode instead of making a land waypoint.

Also, it’s probably poor practice to use 0 as the message severity for all GCS messages. See this table for MAVLink message severity definitions.

I would like to have the possibility on a LR flight to find a landing place in case of problems. For this I fly over an area and then set the waypoint for landing with this script.

The Land flight mode might also work, but with the LUA script I hope to be able to specify exactly where to land.

It is a test script insofar, because I still have to test this saving of the waypoint in real.

I guess that makes sense as a sort of real-time means of selecting a landing site.

You can always test in SITL with a joystick connected to replicate your transmitter (or just hard-code a switch position for the express purpose of testing via SITL - just don’t forget to remove that line when you move the script to the vehicle!).

Arducopter has the RCn_Option 7 (Save Waypoint), which Arduplane unfortunately does not know. Maybe it is possible to port the function adapted to Arduplane.
SAVE_WP in ardupilot/RC_Channel.cpp at master · ArduPilot/ardupilot · GitHub.

I still have to deal with SITL …

I tested some more. When mission:clear() is used, no waypoint is ever saved. No idea how to clear a mission by script … But in principle it doesn’t matter if I always save the LAND waypoint at position 1.

What firmware version and frame type are you using? I’ll do some testing of my own and see what happens. I don’t see any glaring errors in your script.

As for the SAVE_WP function, it seems odd that ArduPlane doesn’t support it, but that is of little consequence. You’d still need some scripted interaction to change the command from 16 to 21, and it seems a large burden to craft an entire build environment and make a custom firmware build just for that feature.

SAVE_WP has the RCn_option 7. The option with a number 7 does not exist in Arduplane. It seems that in Plane and Copter there are gaps in the numbering of the non-existent options.

Firmware is Arduplane 4.1.2 / Plane = Albabird Twin-Mot

I do not plan to do a custom build. With Pitlab you can create a landing sequence during the flight. This is not possible with ArduPlane directly, but let’s see how far we can get with a LUA script.

Hi Rolf ;-).

@Rolf, I’m familiar with the function and use it in Rover. I can also see from the parameter list for Plane that it is not enabled. Plane and Copter are significantly different branches for reasons that are pretty apparent. If you had a need for SAVE_WP in Plane, you could always create an issue on GitHub to bring it to the devs’ attention. It’s not really useful in this particular case, though.

1 Like

Well, the answer is a little more painful than I expected, but the problem with using mission:clear() the way that you did is that it also completely kills the home waypoint, which is a necessary value. So you must re-create it before adding another waypoint to the mission. Also, you should check for the switch position changing rather than just checking for the present switch position, lest you accidentally trigger the save function more than once.

local LOW  = 0
local MID  = 1
local HIGH = 2

local WAYPOINT    = 16
local LAND        = 21

local last_sw_pos = -1

local scripting_rc_1 = rc:find_channel_for_option(300)

function new_mission()
    local home = ahrs:get_home()
    local item = mavlink_mission_item_int_t()

    mission:clear()

    item:command(WAYPOINT)
    item:x(home:lat())
    item:y(home:lng())
    item:z(home:alt())

    if not mission:set_item(0, item) then
        gcs:send_text(4, "Home waypoint not saved!")
        return false
    end

    return true
end

function save_land_wp(clear_mission)

    if clear_mission then
        if not new_mission() then
            return false
        end
    end

    item = mavlink_mission_item_int_t()

	local instance = gps:primary_sensor()
	local position = gps:location(instance)

    if (not position) then
		gcs:send_text(4, "No position data!")
        return false
    end

    item:command(LAND)
    item:x(position:lat())
    item:y(position:lng())
    item:z(0)

    if not mission:set_item(mission:num_commands(), item) then
        gcs:send_text(4, "LAND wp not saved!")
        return false
    end

    return true
end

function update()

    local sw_pos = scripting_rc_1:get_aux_switch_pos()

    if sw_pos ~= last_sw_pos and sw_pos == HIGH then
        if save_land_wp(false) then  -- call with true to clear mission
            gcs:send_text(6, "LAND wp saved!")
        end
    end

    last_sw_pos = sw_pos

    return update, 100

end

if scripting_rc_1 then
    gcs:send_text(6, 'Save_Land_WP script active')
    return update()
end

gcs:send_text(4, 'RC Function 300 not assigned!')
1 Like

Thank you @Yuri_Rage, I’m still missing some things when it comes to LUA scripts … which is also a little bit due to the available documentation.

Originally I used ahrs:get_position() to get the current GPS position, like you do now with ahrs:get_home() for the home position.

What do you think is better/faster for the intended purpose, getting the position via ahrs:get_position() or via gps:location()? I could imagine that in flight there might be a few meters difference between both options.

Unless you have a reason to disregard AHRS in the cases where this script would be used, it makes far more sense to use AHRS position than the last GPS fix. Especially with Plane, where velocity could be significant, you’ll want AHRS to make up the difference between the last GPS fix and the vehicle’s actual position.

The Lua documentation has always lagged quite a bit. There’s A LOT of material to cover there, and development rapidly outpaces documentation. If you’re making significant use of Lua, it’s crucial to reference the binding generator rather than relying on the Wiki.

1 Like

@Target0815 Hi Reinhard,

Instead of zero elevation ( item:z(0) ) it is better to take terrain elevation. For long distance flights I do not assume that you have always the same terrain height as at the starting point (except in Lower Saxony) :wink:

Rolf

Hi Rolf,

yes, that certainly still needs to be worked out. But now I have a start in LUA and in the first step I will see how exactly the LAND wp can be set in real flight.

That does make sense now that I know you’re not using Copter. Of course, you might want to set up a landing approach as well, but I’m not very well versed in Plane, so I’ll leave that to you unless you need some more help with the syntax alone.