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

Scripting: added copter deploy example #26651

Merged
merged 3 commits into from
Aug 3, 2024
Merged
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
1 change: 1 addition & 0 deletions libraries/AP_Arming/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ class AP_Arming {
// these functions should not be used by Copter which holds the armed state in the motors library
Required arming_required() const;
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
virtual bool arm_force(AP_Arming::Method method) { return arm(method, false); }
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be preferable to check the number of arguments being passed to the C function (lua_gettop?) rather than creating methods like this, IMO.

virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true);
bool is_armed() const;
bool is_armed_and_safety_off() const;
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2107,6 +2107,11 @@ function baro:get_altitude() end
---@return boolean
function baro:healthy(instance) end

-- get altitude difference from a base pressure and current pressure
---@param base_pressure number -- first reference pressure in Pa
---@param pressure number -- 2nd pressure in Pa
---@return number -- altitude difference in meters
function baro:get_altitude_difference(base_pressure,pressure) end

-- Serial ports
serial = {}
Expand Down Expand Up @@ -3193,6 +3198,10 @@ function arming:get_aux_auth_id() end
---@return boolean -- true if armed successfully
function arming:arm() end

-- force arm the vehicle
---@return boolean -- true if armed
function arming:arm_force() end

-- Returns a true if vehicle is currently armed.
---@return boolean -- true if armed
function arming:is_armed() end
Expand Down
84 changes: 84 additions & 0 deletions libraries/AP_Scripting/examples/copter_deploy.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
--[[
script to auto-deploy a vehicle on descent after reaching a specified altitude
uses raw pressure to not depend on either GPS or on home alt
--]]
local PARAM_TABLE_KEY = 72
local PARAM_TABLE_PREFIX = "DEPL_"
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

---@diagnostic disable: missing-parameter
---@diagnostic disable: param-type-mismatch

-- bind a parameter to a variable
function bind_param(name)
local p = Parameter()
assert(p:init(name), string.format('could not find %s parameter', name))
return p
end

-- add a parameter and bind it to a variable
function bind_add_param(name, idx, default_value)
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
return bind_param(PARAM_TABLE_PREFIX .. name)
end

assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add param table')

local end_pos = bind_add_param('OPEN_POS', 1, 1200)
local offset = bind_add_param('OPEN_OFFSET', 2, 400)
local deployment_alt = bind_add_param('ALT', 3, 1)
local DEPL_CLIMB_ALT = bind_add_param('CLIMB_ALT', 4, 2)
local base_pressure = nil
local SERVO_FUNCTION = 94
local reached_climb_alt = false
local deployed = false

local MODE_LAND = 9

function update_state()
local pressure = baro:get_pressure()
if not pressure then
return
end
if not base_pressure then
base_pressure = pressure
end
local altitude = baro:get_altitude_difference(base_pressure, pressure)
if not altitude then
return
end
gcs:send_named_float('DALT',altitude)
logger.write("DEPL",'BP,P,Alt','fff',
base_pressure, pressure, altitude)
if not reached_climb_alt then
local start_pos = end_pos:get() + offset:get()
SRV_Channels:set_output_pwm(SERVO_FUNCTION, start_pos)
if altitude > DEPL_CLIMB_ALT:get() then
reached_climb_alt = true
gcs:send_text(MAV_SEVERITY.ERROR, "DEPL: Reached climb alt")
end
return
end
if deployed then
return
end
if altitude > deployment_alt:get() then
return
end
deployed = true
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: deploying")
vehicle:set_mode(MODE_LAND)
arming:arm_force()
if not vehicle:get_mode() == MODE_LAND or not arming:is_armed() then
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: Arming failed")
return
end
--SRV_Channels:set_output_pwm(SERVO_FUNCTION, end_pos:get())
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: Deployed successfully")
end
function update() -- this is the loop which periodically runs
update_state()
return update, 20 -- Reschedules the loop at 50Hz
end
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: loaded")
return update() -- Run immediately before starting to reschedule
2 changes: 2 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ singleton AP_Arming method disarm boolean AP_Arming::Method::SCRIPTING'literal
singleton AP_Arming method is_armed boolean
singleton AP_Arming method pre_arm_checks boolean false'literal
singleton AP_Arming method arm boolean AP_Arming::Method::SCRIPTING'literal
singleton AP_Arming method arm_force boolean AP_Arming::Method::SCRIPTING'literal
singleton AP_Arming method get_aux_auth_id boolean uint8_t'Null
singleton AP_Arming method set_aux_auth_passed void uint8_t'skip_check
singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string
Expand Down Expand Up @@ -418,6 +419,7 @@ singleton AP_Baro method get_temperature float
singleton AP_Baro method get_external_temperature float
singleton AP_Baro method get_altitude float
singleton AP_Baro method healthy boolean uint8_t'skip_check
singleton AP_Baro method get_altitude_difference float float'skip_check float'skip_check

include AP_OpticalFlow/AP_OpticalFlow.h
singleton AP_OpticalFlow depends AP_OPTICALFLOW_ENABLED
Expand Down
Loading