-
Notifications
You must be signed in to change notification settings - Fork 19.9k
Description
Feature request
We have a fixed-wing plane which has a complicated landing sequence, which forces us to always land in AUTO mode using RTL_AUTOLAND parameter. However, this means that RTL_ALTITUDE is ignored, since the vehicle always proceeds to the first waypoint after MAV_CMD_DO_LAND_START. I also need a way to support "return at current altitude", set when parameter is equal to -1.
The landing sequence contains MAV_CMD_NAV_LOITER_TO_ALT at 50m AGL which is required for final approach, but the plane glides to it in a straight descending line, potentially crashing into terrain.
I would like the vehicle to complete the RTL route on altitude set in RTL_ALTITUDE parameter, also when landing in AUTO mode, and only descend when close to landing sequence.
Workaround
By adding a MAV_CMD_NAV_WAYPOINT after MAV_CMD_DO_LAND_START and before MAV_CMD_NAV_LOITER_TO_ALT, I can adjust the return altitude on this mission item, and have the plane climb to it immediately by setting bit 14 of FLIGHT_OPTIONS. I am including the Lua function below.
The problem is, that this script needs to reliably detect when RTL mode is triggered to update the waypoint. When using RTL_AUTOLAND the vehicle switches to AUTO immediately, and I might miss it between the calls of the script. When changing the mode from GCS, I can listen to MAV_CMD_DO_SET_MODE, but can't detect RTL triggered by another script or RC transmitter. Finally, I can't simply look at the index of current waypoint, because I don't want to climb to RTL altitude when mission proceeds to landing sequence as planned.
Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[x ] Plane
[ ] Rover
[ ] Submarine
Additional context
I'd be happy to contribute either a reliable way to detect RTL in Lua when using Automatic landing or some more involved behaviour for RTL, as preferred by the dev team.
I searched the issues for RTL_AUTOLAND and RTL_ALTITUDE but didn't find anything with both for my use case. There's a thread Altitude behaviour on RTL using DO_LAND_START with RTL_AUTOLAND=2 which confirms that adding a waypoint is the way to do it.
-- Update first waypoint of landing sequence to recreate RTL_ALTITUDE behavior in AUTO
--
-- This must be called every time the vehicle enters RTL. Because the altitude target is specified
-- as a regular waypoint with large acceptance radius, the vehicle might not reach it if it's already close.
-- Note that if RTL is switched into AUTO and vehicle continues the mission it will fly to RTL altitude,
-- this can be reset to original value by reuploading the mission plan from GCS.
local function update_rtl_altitude()
local doland_idx = find_do_land_start_index()
if not doland_idx then
return
end
local rtl_idx = doland_idx + 1
local rtl_item = mission:get_item(rtl_idx)
if (not rtl_item) or rtl_item:command() ~= MAV_CMD_NAV_WAYPOINT then
return
end
local rtl_altitude = RTL_ALTITUDE:get()
if not rtl_altitude then
return
end
if rtl_altitude == -1 then
local current_rel_alt = -ahrs:get_relative_position_D_home()
rtl_item:z(current_rel_alt)
else
rtl_item:z(rtl_altitude)
end
-- Never write altitude smaller than 50 m
if rtl_item:z() < 50 then
rtl_item:z(50)
end
-- Ensure the altitude is relative to home like the parameter
rtl_item:frame(MAV_FRAME_GLOBAL_RELATIVE_ALT)
mission:set_item(rtl_idx, rtl_item)
gcs:send_text(MAV_SEVERITY.NOTICE, string.format("Doing RTL at %.0f m (REL)", rtl_item:z()))
-- If already flying there, update the navigation target after mission was modified
if mission:get_current_nav_index() == rtl_idx then
mission:set_current_cmd(rtl_idx)
end
endContribution on behalf of @FlyfocusUAV