Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: add Lua bindings to check VTOL approach and land phases #27531

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
51 changes: 26 additions & 25 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -636,31 +636,6 @@ class QuadPlane
QAutoTune qautotune;
#endif

/*
are we in the approach phase of a VTOL landing?
*/
bool in_vtol_land_approach(void) const;

/*
are we in the final landing phase of a VTOL landing?
*/
bool in_vtol_land_final(void) const;

/*
are we in any of the phases of a VTOL landing?
*/
bool in_vtol_land_sequence(void) const;

/*
see if we are in the VTOL position control phase of a landing
*/
bool in_vtol_land_poscontrol(void) const;

/*
are we in the airbrake phase of a VTOL landing?
*/
bool in_vtol_airbrake(void) const;

// returns true if the vehicle should currently be doing a spiral landing
bool landing_with_fixed_wing_spiral_approach(void) const;

Expand Down Expand Up @@ -720,6 +695,32 @@ class QuadPlane
MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,
uint16_t throttle_value, float timeout_sec,
uint8_t motor_count);

/*
are we in the approach phase of a VTOL landing?
*/
bool in_vtol_land_approach(void) const;

/*
are we in the final landing phase of a VTOL landing?
*/
bool in_vtol_land_final(void) const;

/*
are we in any of the phases of a VTOL landing?
*/
bool in_vtol_land_sequence(void) const;

/*
see if we are in the VTOL position control phase of a landing
*/
bool in_vtol_land_poscontrol(void) const;

/*
are we in the airbrake phase of a VTOL landing?
*/
bool in_vtol_airbrake(void) const;

private:
void motor_test_stop();

Expand Down
30 changes: 25 additions & 5 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1809,22 +1809,42 @@ function sub:set_rangefinder_target_cm(new_target_cm) end
-- desc
quadplane = {}

-- desc
-- true when in the airbrake stage of VTOL approach
---@return boolean
function quadplane:in_assisted_flight() end
function quadplane:in_vtol_airbrake() end

-- desc
-- true when in the position control stage of VTOL landing
---@return boolean
function quadplane:in_vtol_mode() end
function quadplane:in_vtol_land_poscontrol() end

-- true when in any stage of VTOL approach and landing
---@return boolean
function quadplane:in_vtol_land_sequence() end

-- true when in the final stage of VTOL landing
---@return boolean
function quadplane:in_vtol_land_final() end

-- true in descent phase of VTOL landing
-- true when in the approach phase of VTOL landing
---@return boolean
function quadplane:in_vtol_land_approach() end

-- true when in descent phase of VTOL landing
---@return boolean
function quadplane:in_vtol_land_descent() end

-- abort a VTOL landing, climbing back up
---@return boolean
function quadplane:abort_landing() end

-- true when in VTOL assisted flight
---@return boolean
function quadplane:in_assisted_flight() end

-- true when in VTOL modes
---@return boolean
function quadplane:in_vtol_mode() end


-- desc
LED = {}
Expand Down
51 changes: 51 additions & 0 deletions libraries/AP_Scripting/examples/vtol_land_status.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
--[[
Example script to test VTOL approach bindings. Prints a message to the console once in the VTOL land sequence
indicating which phase of the approach and landing the aircraft is in.
]]--

-- Function to retrieve VTOL status
function get_vtol_status()
-- Retrieve the status from the QuadPlane methods
local in_vtol_land_approach = quadplane:in_vtol_land_approach()
local in_vtol_land_final = quadplane:in_vtol_land_final()
local in_vtol_land_poscontrol = quadplane:in_vtol_land_poscontrol()
local in_vtol_airbrake = quadplane:in_vtol_airbrake()

-- Return the status as a table
return {
approach = in_vtol_land_approach,
final = in_vtol_land_final,
poscontrol = in_vtol_land_poscontrol,
airbrake = in_vtol_airbrake
}
end

-- Function to send VTOL status to GCS
function send_status_to_gcs()
-- Get the VTOL status
local status = get_vtol_status()

-- Create the message to send to the GCS
local message = string.format("VTOL Status - Approach: %s, Final: %s, PosControl: %s, Airbrake: %s",
tostring(status.approach),
tostring(status.final),
tostring(status.poscontrol),
tostring(status.airbrake))
-- Send the message to the GCS if in VTOL land sequence
gcs:send_text(6, message)
end

-- Main update function
function update()

-- Call the function to send status to GCS
if quadplane:in_vtol_land_sequence() then
send_status_to_gcs()
end

-- Schedule the next run of this function in 1000 ms (1 Hz)
return update, 1000
end

-- Start the main loop
return update, 1000
5 changes: 5 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -539,6 +539,11 @@ singleton QuadPlane method in_vtol_mode boolean
singleton QuadPlane method in_assisted_flight boolean
singleton QuadPlane method abort_landing boolean
singleton QuadPlane method in_vtol_land_descent boolean
singleton QuadPlane method in_vtol_land_approach boolean
singleton QuadPlane method in_vtol_land_final boolean
singleton QuadPlane method in_vtol_land_sequence boolean
singleton QuadPlane method in_vtol_land_poscontrol boolean
singleton QuadPlane method in_vtol_airbrake boolean

include ../ArduSub/Sub.h depends APM_BUILD_TYPE(APM_BUILD_ArduSub)
singleton Sub rename sub
Expand Down
Loading