Skip to content

Commit

Permalink
AP_Scripting: update copter-posoffset
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Oct 2, 2024
1 parent 4d8e9f6 commit 689cbd4
Showing 1 changed file with 36 additions and 4 deletions.
40 changes: 36 additions & 4 deletions libraries/AP_Scripting/examples/copter-posoffset.lua
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
--
-- How To Use
-- 1. copy this script to the autopilot's "scripts" directory
-- 2. within the "scripts" directory create a "modules" directory
-- 3. copy the MAVLink/mavlink_msgs_xxx files to the "scripts" directory
--
-- 2. set PSC_OFS_xx parameter to the desired position OR velocity offsets desired
-- 3. fly the vehicle in Auto mode (or almost any mode)
-- 4. use the Scripting1 aux switch to enable and disable the offsets

local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

Expand Down Expand Up @@ -83,13 +83,45 @@ local PSC_OFS_VEL_E = bind_add_param("VEL_E", 5, 0)
--]]
local PSC_OFS_VEL_D = bind_add_param("VEL_D", 6, 0)

-- local variables
local aux_sw_pos_last = 0

-- welcome message to user
gcs:send_text(MAV_SEVERITY.INFO, "copter-posoffset.lua loaded")

function update()

-- must be armed, flying and in auto mode
if (not arming:is_armed()) or (not vehicle:get_likely_flying()) then
return update, 1000
end

-- Scripting1 aux switch enables/disables offsets
local aux_sw_pos = rc:get_aux_cached(300)
if aux_sw_pos == nil then
aux_sw_pos = 0
end

-- check for change in aux switch position
if aux_sw_pos ~= aux_sw_pos_last then
aux_sw_pos_last = aux_sw_pos
if aux_sw_pos == 0 then
-- if switch is in low position clear offsets
if poscontrol:set_posvelaccel_offset(Vector3f(), Vector3f(), Vector3f()) then
gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: offsets cleared")
return update, 1000
else
gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to clear offsets")
end
else
gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: offsets activated")
end
end

if aux_sw_pos == 0 then
return update, 1000
end

local pos_offsets_zero = PSC_OFS_POS_N:get() == 0 and PSC_OFS_POS_E:get() == 0 and PSC_OFS_POS_D:get() == 0
local vel_offsets_zero = PSC_OFS_VEL_N:get() == 0 and PSC_OFS_VEL_E:get() == 0 and PSC_OFS_VEL_D:get() == 0

Expand All @@ -111,7 +143,7 @@ function update()
print_warning("unable to get position offset")
pos_offset_NED = Vector3f()
end
-- set velocity offsets in m/s in NED frame
-- test velocity offsets in m/s in NED frame
local vel_offset_NED = Vector3f()
vel_offset_NED:x(PSC_OFS_VEL_N:get())
vel_offset_NED:y(PSC_OFS_VEL_E:get())
Expand Down

0 comments on commit 689cbd4

Please sign in to comment.