2022-10-26 00:48:24 -03:00
|
|
|
--[[
|
|
|
|
trajectory tracking aerobatic control
|
|
|
|
See README.md for usage
|
|
|
|
Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
|
|
|
|
assistance from Paul Riseborough, testing by Henry Wurzburg
|
2022-09-15 00:52:13 -03:00
|
|
|
]]--
|
|
|
|
|
|
|
|
-- setup param block for aerobatics, reserving 30 params beginning with AERO_
|
|
|
|
local PARAM_TABLE_KEY = 70
|
|
|
|
local PARAM_TABLE_PREFIX = 'AEROM_'
|
|
|
|
assert(param:add_table(PARAM_TABLE_KEY, "AEROM_", 30), 'could not add param table')
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- add a parameter and bind it to a variable
|
2022-09-15 00:52:13 -03:00
|
|
|
function bind_add_param(name, idx, default_value)
|
2022-10-06 03:05:31 -03:00
|
|
|
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
|
|
|
|
return Parameter(PARAM_TABLE_PREFIX .. name)
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
HGT_P = bind_add_param('HGT_P', 1, 1)
|
|
|
|
HGT_I = bind_add_param('HGT_I', 2, 2)
|
|
|
|
HGT_KE_BIAS = bind_add_param('HGT_KE_ADD', 3, 20)
|
|
|
|
THR_PIT_FF = bind_add_param('THR_PIT_FF', 4, 80)
|
|
|
|
SPD_P = bind_add_param('SPD_P', 5, 5)
|
|
|
|
SPD_I = bind_add_param('SPD_I', 6, 25)
|
|
|
|
ERR_CORR_TC = bind_add_param('ERR_COR_TC', 7, 3)
|
|
|
|
ROLL_CORR_TC = bind_add_param('ROL_COR_TC', 8, 0.25)
|
|
|
|
AUTO_MIS = bind_add_param('AUTO_MIS', 9, 0)
|
|
|
|
AUTO_RAD = bind_add_param('AUTO_RAD', 10, 40)
|
|
|
|
TIME_CORR_P = bind_add_param('TIME_COR_P', 11, 1.0)
|
|
|
|
ERR_CORR_P = bind_add_param('ERR_COR_P', 12, 2.0)
|
|
|
|
ERR_CORR_D = bind_add_param('ERR_COR_D', 13, 2.8)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
--[[
|
|
|
|
Aerobatic tricks on a switch support - allows for tricks to be initiated outside AUTO mode
|
|
|
|
--]]
|
|
|
|
-- 2nd param table for tricks on a switch
|
|
|
|
local PARAM_TABLE_KEY2 = 71
|
|
|
|
local PARAM_TABLE_PREFIX2 = "TRIK"
|
|
|
|
assert(param:add_table(PARAM_TABLE_KEY2, PARAM_TABLE_PREFIX2, 63), 'could not add param table2')
|
|
|
|
|
|
|
|
-- add a parameter and bind it to a variable in table2
|
|
|
|
function bind_add_param2(name, idx, default_value)
|
|
|
|
assert(param:add_param(PARAM_TABLE_KEY2, idx, name, default_value), string.format('could not add param %s', name))
|
|
|
|
return Parameter(PARAM_TABLE_PREFIX2 .. name)
|
|
|
|
end
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
local TRIK_ENABLE = bind_add_param2("_ENABLE", 1, 0)
|
|
|
|
local TRICKS = nil
|
|
|
|
local TRIK_SEL_FN = nil
|
|
|
|
local TRIK_ACT_FN = nil
|
|
|
|
local TRIK_COUNT = nil
|
|
|
|
|
|
|
|
local function TrickDef(id, arg1, arg2, arg3, arg4)
|
|
|
|
local self = {}
|
|
|
|
self.id = id
|
|
|
|
self.args = {arg1, arg2, arg3, arg4}
|
|
|
|
return self
|
|
|
|
end
|
|
|
|
|
|
|
|
-- constrain a value between limits
|
|
|
|
function constrain(v, vmin, vmax)
|
|
|
|
if v < vmin then
|
|
|
|
v = vmin
|
|
|
|
end
|
|
|
|
if v > vmax then
|
|
|
|
v = vmax
|
|
|
|
end
|
|
|
|
return v
|
|
|
|
end
|
|
|
|
|
|
|
|
if TRIK_ENABLE:get() > 0 then
|
|
|
|
TRIK_SEL_FN = bind_add_param2("_SEL_FN", 2, 301)
|
|
|
|
TRIK_ACT_FN = bind_add_param2("_ACT_FN", 3, 300)
|
|
|
|
TRIK_COUNT = bind_add_param2("_COUNT", 4, 3)
|
|
|
|
TRICKS = {}
|
|
|
|
|
|
|
|
-- setup parameters for tricks
|
|
|
|
local count = math.floor(constrain(TRIK_COUNT:get(),1,11))
|
|
|
|
for i = 1, count do
|
|
|
|
local k = 5*i
|
|
|
|
local prefix = string.format("%u", i)
|
|
|
|
TRICKS[i] = TrickDef(bind_add_param2(prefix .. "_ID", k+0, i),
|
|
|
|
bind_add_param2(prefix .. "_ARG1", k+1, 30),
|
|
|
|
bind_add_param2(prefix .. "_ARG2", k+2, 0),
|
|
|
|
bind_add_param2(prefix .. "_ARG3", k+3, 0),
|
|
|
|
bind_add_param2(prefix .. "_ARG4", k+4, 0))
|
|
|
|
end
|
|
|
|
gcs:send_text(0, string.format("Enabled %u aerobatic tricks", TRIK_COUNT:get()))
|
2022-10-06 03:05:31 -03:00
|
|
|
end
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local NAV_TAKEOFF = 22
|
|
|
|
local NAV_WAYPOINT = 16
|
|
|
|
local NAV_SCRIPT_TIME = 42702
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
local MODE_AUTO = 10
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
local LOOP_RATE = 20
|
2022-10-25 02:43:03 -03:00
|
|
|
local DO_JUMP = 177
|
|
|
|
local k_throttle = 70
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local TRIM_ARSPD_CM = Parameter("TRIM_ARSPD_CM")
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
local last_id = 0
|
2022-10-25 02:43:03 -03:00
|
|
|
local current_task = nil
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
function wrap_360(angle)
|
|
|
|
local res = math.fmod(angle, 360.0)
|
|
|
|
if res < 0 then
|
|
|
|
res = res + 360.0
|
|
|
|
end
|
|
|
|
return res
|
|
|
|
end
|
|
|
|
|
|
|
|
function wrap_180(angle)
|
|
|
|
local res = wrap_360(angle)
|
|
|
|
if res > 180 then
|
|
|
|
res = res - 360
|
|
|
|
end
|
|
|
|
return res
|
|
|
|
end
|
|
|
|
|
|
|
|
function wrap_pi(angle)
|
|
|
|
local angle_deg = math.deg(angle)
|
|
|
|
local angle_wrapped = wrap_180(angle_deg)
|
|
|
|
return math.rad(angle_wrapped)
|
|
|
|
end
|
|
|
|
|
|
|
|
function wrap_2pi(angle)
|
|
|
|
local angle_deg = math.deg(angle)
|
|
|
|
local angle_wrapped = wrap_360(angle_deg)
|
|
|
|
return math.rad(angle_wrapped)
|
|
|
|
end
|
|
|
|
|
|
|
|
-- a PI controller implemented as a Lua object
|
|
|
|
local function PI_controller(kP,kI,iMax)
|
|
|
|
-- the new instance. You can put public variables inside this self
|
|
|
|
-- declaration if you want to
|
|
|
|
local self = {}
|
|
|
|
|
|
|
|
-- private fields as locals
|
|
|
|
local _kP = kP or 0.0
|
|
|
|
local _kI = kI or 0.0
|
|
|
|
local _kD = kD or 0.0
|
|
|
|
local _iMax = iMax
|
|
|
|
local _last_t = nil
|
|
|
|
local _I = 0
|
|
|
|
local _P = 0
|
|
|
|
local _total = 0
|
|
|
|
local _counter = 0
|
|
|
|
local _target = 0
|
|
|
|
local _current = 0
|
|
|
|
|
|
|
|
-- update the controller.
|
|
|
|
function self.update(target, current)
|
|
|
|
local now = millis():tofloat() * 0.001
|
|
|
|
if not _last_t then
|
|
|
|
_last_t = now
|
|
|
|
end
|
|
|
|
local dt = now - _last_t
|
|
|
|
_last_t = now
|
|
|
|
local err = target - current
|
|
|
|
_counter = _counter + 1
|
|
|
|
|
|
|
|
local P = _kP * err
|
|
|
|
_I = _I + _kI * err * dt
|
|
|
|
if _iMax then
|
|
|
|
_I = constrain(_I, -_iMax, iMax)
|
|
|
|
end
|
|
|
|
local I = _I
|
|
|
|
local ret = P + I
|
|
|
|
|
|
|
|
_target = target
|
|
|
|
_current = current
|
|
|
|
_P = P
|
|
|
|
_total = ret
|
|
|
|
return ret
|
|
|
|
end
|
|
|
|
|
|
|
|
-- reset integrator to an initial value
|
|
|
|
function self.reset(integrator)
|
|
|
|
_I = integrator
|
|
|
|
end
|
|
|
|
|
|
|
|
function self.set_I(I)
|
|
|
|
_kI = I
|
|
|
|
end
|
|
|
|
|
|
|
|
function self.set_P(P)
|
|
|
|
_kP = P
|
|
|
|
end
|
|
|
|
|
|
|
|
function self.set_Imax(Imax)
|
|
|
|
_iMax = Imax
|
|
|
|
end
|
|
|
|
|
|
|
|
-- log the controller internals
|
|
|
|
function self.log(name, add_total)
|
|
|
|
-- allow for an external addition to total
|
|
|
|
logger.write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total)
|
|
|
|
end
|
|
|
|
-- return the instance
|
|
|
|
return self
|
|
|
|
end
|
|
|
|
|
2022-09-22 02:56:21 -03:00
|
|
|
local function speed_controller(kP_param,kI_param, kFF_roll_param, kFF_pitch_param, Imax)
|
|
|
|
local self = {}
|
|
|
|
local kFF_roll = kFF_roll_param
|
|
|
|
local kFF_pitch = kFF_pitch_param
|
|
|
|
local PI = PI_controller(kP_param:get(), kI_param:get(), Imax)
|
|
|
|
|
|
|
|
function self.update(target)
|
|
|
|
local current_speed = ahrs:get_velocity_NED():length()
|
|
|
|
local throttle = PI.update(target, current_speed)
|
|
|
|
throttle = throttle + math.sin(ahrs:get_pitch())*kFF_pitch:get()
|
|
|
|
throttle = throttle + math.abs(math.sin(ahrs:get_roll()))*kFF_roll:get()
|
|
|
|
return throttle
|
|
|
|
end
|
|
|
|
|
|
|
|
function self.reset()
|
|
|
|
PI.reset(0)
|
|
|
|
local temp_throttle = self.update(ahrs:get_velocity_NED():length())
|
|
|
|
local current_throttle = SRV_Channels:get_output_scaled(k_throttle)
|
|
|
|
PI.reset(current_throttle-temp_throttle)
|
|
|
|
end
|
|
|
|
|
|
|
|
return self
|
|
|
|
end
|
|
|
|
|
|
|
|
local speed_PI = speed_controller(SPD_P, SPD_I, HGT_KE_BIAS, THR_PIT_FF, 100.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-24 02:41:59 -03:00
|
|
|
function sgn(x)
|
|
|
|
local eps = 0.000001
|
|
|
|
if (x > eps) then
|
|
|
|
return 1.0
|
|
|
|
elseif x < eps then
|
|
|
|
return -1.0
|
|
|
|
else
|
|
|
|
return 0.0
|
|
|
|
end
|
|
|
|
end
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
function get_wp_location(i)
|
|
|
|
local m = mission:get_item(i)
|
|
|
|
local loc = Location()
|
|
|
|
loc:lat(m:x())
|
|
|
|
loc:lng(m:y())
|
2022-10-06 03:05:31 -03:00
|
|
|
loc:relative_alt(true)
|
2022-09-15 00:52:13 -03:00
|
|
|
loc:terrain_alt(false)
|
|
|
|
loc:origin_alt(false)
|
|
|
|
loc:alt(math.floor(m:z()*100))
|
|
|
|
return loc
|
|
|
|
end
|
|
|
|
|
|
|
|
function resolve_jump(i)
|
|
|
|
local m = mission:get_item(i)
|
|
|
|
while m:command() == DO_JUMP do
|
|
|
|
i = math.floor(m:param1())
|
|
|
|
m = mission:get_item(i)
|
|
|
|
end
|
|
|
|
return i
|
|
|
|
end
|
|
|
|
|
|
|
|
--------Trajectory definitions---------------------
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function climbing_circle(t, radius, height, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
local angle = t*math.pi*2
|
|
|
|
local vec = makeVector3f(radius*math.sin(angle), radius*(1.0-math.cos(angle)), -math.sin(0.5*angle)*height)
|
|
|
|
return vec, 0.0
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function figure_eight(t, r, bank_angle, arg3, arg4)
|
2022-10-24 02:41:59 -03:00
|
|
|
|
|
|
|
local r_sign = sgn(r)
|
|
|
|
assert(math.abs(r_sign) > 0.1)
|
|
|
|
local r = math.abs(r)
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local T = 3.0*math.pi*r + r*math.sqrt(2) + 2*r
|
|
|
|
|
|
|
|
local rsqr2 = r*math.sqrt(2)
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
if (t < rsqr2/T) then
|
|
|
|
pos = makeVector3f(T*t, 0.0, 0.0)
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - math.sqrt(2) - math.pi/2)+rsqr2, (r + r*math.sin(T*t/r - math.sqrt(2) - math.pi/2)), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = math.rad(bank_angle)
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r/4)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + 3*r/4)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r*math.cos(-T*t/r +5.0*math.pi/4.0 + math.sqrt(2) + 1 - math.pi/4) - r*math.sqrt(2.0), (r + r*math.sin(-T*t/r +5.0*math.pi/4.0 + math.sqrt(2) + 1 - math.pi/4)), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = -math.rad(bank_angle)
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + r/4.0)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + 3*r/4.0)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + r)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), (r +r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = 0.0
|
|
|
|
else
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - (6*math.pi/4.0 + math.sqrt(2) +2 ))+rsqr2, (r + r*math.sin(T*t/r - (6*math.pi/4.0 + math.sqrt(2) +2 ))), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = math.rad(bank_angle)
|
|
|
|
end
|
2022-10-26 00:38:34 -03:00
|
|
|
|
|
|
|
if r_sign == -1 then
|
|
|
|
pos:y(-pos:y())
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
return pos, roll
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function loop(t, radius, bank_angle, arg3, arg4)
|
|
|
|
local num_loops = math.abs(arg3)
|
|
|
|
if(arg3 <= 0.0) then
|
|
|
|
num_loops = 1
|
|
|
|
end
|
|
|
|
|
|
|
|
t = num_loops*t*math.pi*2
|
2022-09-15 00:52:13 -03:00
|
|
|
local vec = makeVector3f(math.sin(t), 0.0, -1.0 + math.cos(t))
|
2022-10-06 03:05:31 -03:00
|
|
|
return vec:scale(radius), math.rad(bank_angle)
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function straight_roll(t, length, num_rolls, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
local vec = makeVector3f(t*length, 0.0, 0.0)
|
|
|
|
return vec, t*num_rolls*2*math.pi
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function straight_flight(t, length, bank_angle, arg3, arg4)
|
2022-10-06 01:49:19 -03:00
|
|
|
local pos = makeVector3f(t*length, 0, 0)
|
|
|
|
local roll = math.rad(bank_angle)
|
|
|
|
return pos, roll
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function rolling_circle(t, radius, num_rolls, arg3, arg4)
|
2022-09-22 02:56:21 -03:00
|
|
|
local vec = Vector3f()
|
|
|
|
if radius < 0.0 then
|
|
|
|
vec = makeVector3f(math.sin(2*math.pi*t), -1.0+math.cos(2*math.pi*t), 0)
|
|
|
|
else
|
|
|
|
vec = makeVector3f(math.sin(2*math.pi*t), 1.0-math.cos(2*math.pi*t), 0)
|
|
|
|
end
|
|
|
|
return vec:scale(math.abs(radius)), t*num_rolls*2*math.pi
|
|
|
|
end
|
|
|
|
|
2022-10-26 00:38:34 -03:00
|
|
|
function banked_circle(t, radius, bank_angle, height, arg4)
|
2022-09-22 02:56:21 -03:00
|
|
|
local vec = Vector3f()
|
2022-10-26 00:38:34 -03:00
|
|
|
local rad = math.abs(radius)
|
|
|
|
vec = makeVector3f(rad*math.sin(2*math.pi*t), -rad*(-1.0+math.cos(2*math.pi*t)), -height*t)
|
|
|
|
if radius < 0 then
|
|
|
|
vec:y(-vec:y())
|
2022-09-22 02:56:21 -03:00
|
|
|
end
|
2022-10-26 00:38:34 -03:00
|
|
|
return vec, bank_angle
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function half_cuban_eight(t, r, unused, arg3, arg4)
|
2022-10-06 01:49:19 -03:00
|
|
|
local T = 3.0*math.pi*r/2.0 + 2*r*math.sqrt(2) + r
|
|
|
|
|
|
|
|
local trsqr2 = 2*r*math.sqrt(2)
|
|
|
|
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
if (t < trsqr2/T) then
|
|
|
|
pos = makeVector3f(T*t, 0.0, 0.0)
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (trsqr2 + 5.0*math.pi*r/4.0)/T) then
|
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - 2*math.sqrt(2) - math.pi/2)+trsqr2, 0, -r - r*math.sin(T*t/r - 2*math.sqrt(2) - math.pi/2))
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (trsqr2 + 5.0*math.pi*r/4.0 + r/4)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (trsqr2 + 5.0*math.pi*r/4.0 + 3*r/4)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = (t - (trsqr2 + 5.0*math.pi*r/4.0 + r/4)/T)*2*math.pi*T/(r)
|
|
|
|
elseif (t < (trsqr2 + 5.0*math.pi*r/4.0 + r)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = math.pi
|
|
|
|
else
|
|
|
|
pos = makeVector3f(r*math.cos(-T*t/r +5.0*math.pi/4.0 + 2*math.sqrt(2) + 1 - math.pi/4), 0, -r -r*math.sin(-T*t/r +5.0*math.pi/4.0 + 2*math.sqrt(2) + 1 - math.pi/4))
|
|
|
|
roll = math.pi
|
|
|
|
--roll = 0
|
|
|
|
end
|
|
|
|
|
|
|
|
return pos, roll
|
|
|
|
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function cuban_eight(t, r, unused, arg3, arg4)
|
2022-10-06 01:49:19 -03:00
|
|
|
local T = 3.0*math.pi*r + r*math.sqrt(2) + 2*r
|
|
|
|
|
|
|
|
local rsqr2 = r*math.sqrt(2)
|
|
|
|
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
if (t < rsqr2/T) then
|
|
|
|
pos = makeVector3f(T*t, 0.0, 0.0)
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0)/T) then
|
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - math.sqrt(2) - math.pi/2)+rsqr2, 0, -r - r*math.sin(T*t/r - math.sqrt(2) - math.pi/2))
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r/4)/T) then
|
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = 0.0
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + 3*r/4)/T) then
|
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = (t - (rsqr2 + 5.0*math.pi*r/4.0 + r/4)/T)*2*math.pi*T/(r)
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r)/T) then
|
|
|
|
pos = makeVector3f(r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0)/T) then
|
|
|
|
pos = makeVector3f(r*math.cos(-T*t/r +5.0*math.pi/4.0 + math.sqrt(2) + 1 - math.pi/4) - r*math.sqrt(2.0), 0, -r - r*math.sin(-T*t/r +5.0*math.pi/4.0 + math.sqrt(2) + 1 - math.pi/4))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + r/4.0)/T) then
|
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2)))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + 3*r/4.0)/T) then
|
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2)))
|
|
|
|
roll = math.pi +(t - (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + r/4.0)/T)*2 *math.pi*T/(r)
|
|
|
|
elseif (t < (rsqr2 + 5.0*math.pi*r/4.0 + r + 3*math.pi*r/2.0 + r)/T) then
|
|
|
|
pos = makeVector3f(-r/math.sqrt(2) + (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2)*(r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*t/r - 5*math.pi/4 - math.sqrt(2) - 1 - 3*math.pi/2.0 )*(-r*math.sqrt(2)))
|
|
|
|
roll = 0.0
|
|
|
|
else
|
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - (6*math.pi/4.0 + math.sqrt(2) +2 ))+rsqr2, 0, -r - r*math.sin(T*t/r - (6*math.pi/4.0 + math.sqrt(2) +2 )))
|
|
|
|
roll = 0.0
|
|
|
|
end
|
|
|
|
return pos, roll
|
|
|
|
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function half_reverse_cuban_eight(t, r, arg2, arg3, arg4)
|
2022-10-06 01:49:19 -03:00
|
|
|
local T = 3.0*math.pi*r/2.0 + 2*r*math.sqrt(2) + r
|
|
|
|
|
|
|
|
local trsqr2 = 2*r*math.sqrt(2)
|
|
|
|
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
|
|
|
|
|
|
|
|
if(t < (math.pi*r/4)/T) then
|
|
|
|
pos = makeVector3f(r*math.cos(-T*(1-t)/r +5.0*math.pi/4.0 + 2*math.sqrt(2) + 1 - math.pi/4), 0, -r -r*math.sin(-T*(1-t)/r +5.0*math.pi/4.0 + 2*math.sqrt(2) + 1 - math.pi/4))
|
|
|
|
|
|
|
|
roll = 0
|
|
|
|
elseif (t < (math.pi*r/4 + r/4)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = 0
|
|
|
|
elseif (t < (math.pi*r/4 + 3*r/4)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = (t - (math.pi*r/4 + r/4)/T)*2*math.pi*T/(r)
|
|
|
|
elseif (t < (math.pi*r/4 + r)/T) then
|
|
|
|
pos = makeVector3f(3*r/math.sqrt(2) + (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)), 0, -r -r/math.sqrt(2) - (T*(1-t)/r - 5*math.pi/4 - 2*math.sqrt(2))*(-r*math.sqrt(2)))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (3*math.pi*r/2 + r) /T) then
|
|
|
|
pos = makeVector3f(r*math.cos(T*(1-t)/r - 2*math.sqrt(2) - math.pi/2)+trsqr2, 0, -r - r*math.sin(T*(1-t)/r - 2*math.sqrt(2) - math.pi/2))
|
|
|
|
roll = math.pi
|
|
|
|
else
|
|
|
|
pos = makeVector3f(T*(1-t), 0.0, 0.0)
|
|
|
|
roll = math.pi
|
|
|
|
end
|
|
|
|
|
|
|
|
return pos, roll
|
|
|
|
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function humpty_bump(t, r, h, arg3, arg4)
|
|
|
|
assert(h >= 2*r)
|
2022-10-06 01:49:19 -03:00
|
|
|
local T = 2*(math.pi*r + h - r)
|
|
|
|
local l = h - 2*r
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
if (t < (math.pi*r/2)/T) then
|
|
|
|
pos = makeVector3f(r*math.cos(T*t/r - math.pi/2), 0, -r -r*math.sin(T*t/r - math.pi/2))
|
|
|
|
roll = 0
|
|
|
|
elseif (t < (math.pi*r/2 + l/4)/T) then
|
|
|
|
pos = makeVector3f(r, 0, -r -(T*t - r*math.pi/2))
|
|
|
|
roll = 0
|
|
|
|
elseif (t < (math.pi*r/2 + 3*l/4)/T) then
|
|
|
|
pos = makeVector3f(r, 0, -r -(T*t - r*math.pi/2))
|
|
|
|
roll = (t - (math.pi*r/2 + l/4)/T)*2*math.pi*T/l
|
|
|
|
elseif (t < (math.pi*r/2 + l)/T) then
|
|
|
|
pos = makeVector3f(r, 0, -r -(T*t - r*math.pi/2))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (3*math.pi*r/2 + l)/T) then
|
|
|
|
pos = makeVector3f(2*r + r*math.cos(T*t/r - 3*math.pi/2 - l/r), 0, -r-l +r*math.sin(T*t/r - 3*math.pi/2 - l/r))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (3*math.pi*r/2 + 2*l)/T) then
|
|
|
|
pos = makeVector3f(3*r,0, -r -l + (T*t - 3*r*math.pi/2.0 -l))
|
|
|
|
roll = math.pi
|
|
|
|
elseif (t < (2*math.pi*r + 2*l)/T) then
|
2022-10-24 00:05:56 -03:00
|
|
|
pos = makeVector3f(2*r + r*math.cos(T*t/r - 3*math.pi/2 -2*l/r),0, -r + r*math.sin(T*t/r - 3*math.pi/2 -2*l/r))
|
2022-10-06 01:49:19 -03:00
|
|
|
roll = math.pi
|
|
|
|
else
|
|
|
|
pos = makeVector3f(2*r -(T*t - 2*r*math.pi - 2*l), 0, 0)
|
|
|
|
roll = math.pi
|
|
|
|
end
|
|
|
|
return pos, roll
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
function scale_figure_eight(t, r, bank_angle, arg3, arg4)
|
2022-10-24 02:41:59 -03:00
|
|
|
local r_sign = sgn(r)
|
|
|
|
assert(math.abs(r_sign) > 0.1)
|
|
|
|
local r = math.abs(r)
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local T = 4*math.pi + 2
|
|
|
|
local pos
|
|
|
|
local roll
|
|
|
|
if (t < (math.pi/2)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r*math.cos(T*t - math.pi/2), (r +r*math.sin(T*t - math.pi/2)), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = math.rad(bank_angle)
|
|
|
|
elseif (t < (5*math.pi/2)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(2*r + r*math.cos(T*t + math.pi/2), (r -r*math.sin(T*t + math.pi/2)), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = -math.rad(bank_angle)
|
|
|
|
elseif (t < (4*math.pi)/T) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(r*math.cos(T*t - math.pi/2), (r + r*math.sin(T*t - math.pi/2)), 0)
|
2022-10-06 03:05:31 -03:00
|
|
|
roll = math.rad(bank_angle)
|
|
|
|
else
|
|
|
|
pos = makeVector3f(r*(T*t - 4*math.pi), 0, 0)
|
|
|
|
roll = 0
|
|
|
|
end
|
2022-10-26 00:38:34 -03:00
|
|
|
|
|
|
|
if r_sign == -1 then
|
|
|
|
pos:y(-pos:y())
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
return pos, roll
|
|
|
|
end
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
--todo: change y coordinate to z for vertical box
|
|
|
|
--function aerobatic_box(t, l, w, r):
|
2022-10-26 00:38:34 -03:00
|
|
|
function horizontal_rectangle(t, total_length, total_width, r, bank_angle)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-24 02:41:59 -03:00
|
|
|
local r_sign = sgn(r)
|
|
|
|
assert(math.abs(r_sign) > 0.1)
|
|
|
|
local r = math.abs(r)
|
|
|
|
|
2022-10-26 00:38:34 -03:00
|
|
|
local bank_angle = math.abs(bank_angle)
|
2022-10-24 02:41:59 -03:00
|
|
|
local l = total_length - 2*r
|
|
|
|
local w = total_width - 2*r
|
2022-09-15 00:52:13 -03:00
|
|
|
local perim = 2*l + 2*w + 2*math.pi*r
|
|
|
|
local pos
|
|
|
|
if (t < 0.5*l/(perim)) then
|
|
|
|
pos = makeVector3f(perim*t, 0.0, 0.0)
|
|
|
|
elseif (t < (0.5*l + 0.5*math.pi*r)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(0.5*l + r*math.sin((perim*t - 0.5*l)/r), (r*(1 - math.cos((perim*t - 0.5*l)/r))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif (t < (0.5*l + 0.5*math.pi*r + w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(0.5*l + r, (r + (perim*t - (0.5*l + 0.5*math.pi*r))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif(t < (0.5*l + math.pi*r + w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(0.5*l + r + r*(-1 + math.cos((perim*t - (0.5*l + 0.5*math.pi*r + w))/r)), (r + w + r*(math.sin((perim*t - (0.5*l + 0.5*math.pi*r + w))/r))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif(t < (1.5*l + math.pi*r + w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(0.5*l - (perim*t - (0.5*l + math.pi*r + w)), (2*r + w), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif(t < (1.5*l + 1.5*math.pi*r + w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-0.5*l + r*(-math.sin((perim*t - (1.5*l + math.pi*r + w))/r)), (2*r + w + r*(-1 + math.cos((perim*t - (1.5*l + math.pi*r + w))/r))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif(t < (1.5*l + 1.5*math.pi*r + 2*w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-0.5*l -r, (w + r - (perim*t - (1.5*l + 1.5*math.pi*r + w))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
elseif(t < (1.5*l + 2*math.pi*r + 2*w)/perim) then
|
2022-10-26 00:38:34 -03:00
|
|
|
pos = makeVector3f(-0.5*l -r + r*(1 - math.cos((perim*t - (1.5*l + 1.5*math.pi*r + 2*w))/r)), (r + r*(-math.sin((perim*t - (1.5*l + 1.5*math.pi*r + 2*w))/r))), 0.0)
|
2022-09-15 00:52:13 -03:00
|
|
|
else
|
|
|
|
pos = makeVector3f(-0.5*l + perim*t - (1.5*l + 2*math.pi*r + 2*w), 0.0, 0.0)
|
|
|
|
end
|
|
|
|
|
2022-10-26 00:38:34 -03:00
|
|
|
if r_sign == -1 then
|
|
|
|
pos:y(-pos:y())
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
return pos, math.rad(bank_angle)
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-24 02:41:59 -03:00
|
|
|
function vertical_aerobatic_box(t, total_length, total_width, r, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
local q = Quaternion()
|
|
|
|
q:from_euler(-math.rad(90), 0, 0)
|
2022-10-24 02:41:59 -03:00
|
|
|
local point, angle = horizontal_rectangle(t, total_length, total_width, math.abs(r), arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
q:earth_to_body(point)
|
|
|
|
return point, angle
|
|
|
|
end
|
|
|
|
---------------------------------------------------
|
|
|
|
|
2022-10-26 00:59:15 -03:00
|
|
|
--[[
|
|
|
|
target speed is taken as max of target airspeed and current 3D
|
|
|
|
velocity at the start of the maneuver
|
|
|
|
--]]
|
2022-09-15 00:52:13 -03:00
|
|
|
function target_groundspeed()
|
2022-10-26 00:59:15 -03:00
|
|
|
return math.max(ahrs:get_EAS2TAS()*TRIM_ARSPD_CM:get()*0.01, ahrs:get_velocity_NED():length())
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
|
|
|
--Estimate the length of the path in metres
|
2022-10-06 03:05:31 -03:00
|
|
|
function path_length(path_f, arg1, arg2, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
local dt = 0.01
|
|
|
|
local total = 0.0
|
|
|
|
for i = 0, math.floor(1.0/dt) do
|
|
|
|
local t = i*dt
|
|
|
|
local t2 = t + dt
|
2022-10-06 03:05:31 -03:00
|
|
|
local v1 = path_f(t, arg1, arg2, arg3, arg4)
|
|
|
|
local v2 = path_f(t2, arg1, arg2, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
local dv = v2-v1
|
|
|
|
total = total + dv:length()
|
|
|
|
end
|
|
|
|
return total
|
|
|
|
end
|
|
|
|
|
|
|
|
|
|
|
|
--args:
|
|
|
|
-- path_f: path function returning position
|
|
|
|
-- t: normalised [0, 1] time
|
|
|
|
-- arg1, arg2: arguments for path function
|
|
|
|
-- orientation: maneuver frame orientation
|
|
|
|
--returns: requested position in maneuver frame
|
2022-10-06 03:05:31 -03:00
|
|
|
function rotate_path(path_f, t, arg1, arg2, arg3, arg4, orientation, offset)
|
|
|
|
point, angle = path_f(t, arg1, arg2, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
orientation:earth_to_body(point)
|
|
|
|
--TODO: rotate angle?
|
|
|
|
return point+offset, angle
|
|
|
|
end
|
|
|
|
|
|
|
|
--args:
|
|
|
|
-- dt: sample time
|
|
|
|
-- cutoff_freq: cutoff frequency for low pass filter, in Hz
|
|
|
|
--returns: alpha value required to implement LP filter
|
|
|
|
function calc_lowpass_alpha_dt(dt, cutoff_freq)
|
|
|
|
if dt <= 0.0 or cutoff_freq <= 0.0 then
|
|
|
|
return 1.0
|
|
|
|
end
|
|
|
|
|
|
|
|
local rc = 1.0/(2.0*3.14159265*cutoff_freq)
|
|
|
|
local drc = dt/(dt+rc)
|
|
|
|
if drc < 0.0 then
|
|
|
|
return 0.0
|
|
|
|
end
|
|
|
|
if drc > 1.0 then
|
|
|
|
return 1.0
|
|
|
|
end
|
|
|
|
return drc
|
|
|
|
end
|
|
|
|
|
|
|
|
--Wrapper to construct a Vector3f{x, y, z} from (x, y, z)
|
|
|
|
function makeVector3f(x, y, z)
|
|
|
|
local vec = Vector3f()
|
|
|
|
vec:x(x)
|
|
|
|
vec:y(y)
|
|
|
|
vec:z(z)
|
|
|
|
return vec
|
|
|
|
end
|
|
|
|
|
|
|
|
--Given vec1, vec2, returns an (rotation axis, angle) tuple that rotates vec1 to be parallel to vec2
|
|
|
|
--If vec1 and vec2 are already parallel, returns a zero vector and zero angle
|
|
|
|
--Note that the rotation will not be unique.
|
|
|
|
function vectors_to_rotation(vector1, vector2)
|
|
|
|
axis = vector1:cross(vector2)
|
|
|
|
if axis:length() < 0.00001 then
|
|
|
|
local vec = Vector3f()
|
|
|
|
vec:x(1)
|
|
|
|
return vec, 0
|
|
|
|
end
|
|
|
|
axis:normalize()
|
|
|
|
angle = vector1:angle(vector2)
|
|
|
|
return axis, angle
|
|
|
|
end
|
|
|
|
|
|
|
|
--returns Quaternion
|
|
|
|
function vectors_to_rotation_w_roll(vector1, vector2, roll)
|
|
|
|
axis, angle = vectors_to_rotation(vector1, vector2)
|
|
|
|
local vector_rotation = Quaternion()
|
|
|
|
vector_rotation:from_axis_angle(axis, angle)
|
|
|
|
|
|
|
|
local roll_rotation = Quaternion()
|
|
|
|
roll_rotation:from_euler(roll, 0, 0)
|
|
|
|
|
|
|
|
local total_rot = vector_rotation*roll_rotation
|
|
|
|
return to_axis_and_angle(total_rot)
|
|
|
|
end
|
|
|
|
|
|
|
|
--Given vec1, vec2, returns an angular velocity tuple that rotates vec1 to be parallel to vec2
|
|
|
|
--If vec1 and vec2 are already parallel, returns a zero vector and zero angle
|
|
|
|
function vectors_to_angular_rate(vector1, vector2, time_constant)
|
|
|
|
axis, angle = vectors_to_rotation(vector1, vector2)
|
|
|
|
angular_velocity = angle/time_constant
|
|
|
|
return axis:scale(angular_velocity)
|
|
|
|
end
|
|
|
|
|
|
|
|
function vectors_to_angular_rate_w_roll(vector1, vector2, time_constant, roll)
|
|
|
|
axis, angle = vectors_to_rotation_w_roll(vector1, vector2, roll)
|
|
|
|
angular_velocity = angle/time_constant
|
|
|
|
return axis:scale(angular_velocity)
|
|
|
|
end
|
|
|
|
|
|
|
|
function to_axis_and_angle(quat)
|
|
|
|
|
|
|
|
local axis_angle = Vector3f()
|
|
|
|
quat:to_axis_angle(axis_angle)
|
|
|
|
angle = axis_angle:length()
|
|
|
|
if(angle < 0.00001) then
|
|
|
|
return makeVector3f(1.0, 0.0, 0.0), 0.0
|
|
|
|
end
|
|
|
|
return axis_angle:scale(1.0/angle), angle
|
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--projects x onto the othogonal subspace of span(unit_v)
|
|
|
|
function ortho_proj(x, unit_v)
|
|
|
|
local temp_x = unit_v:cross(x)
|
|
|
|
return unit_v:cross(temp_x)
|
|
|
|
end
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- log a pose from position and quaternion attitude
|
|
|
|
function log_pose(logname, pos, quat)
|
|
|
|
logger.write(logname, 'px,py,pz,q1,q2,q3,q4,r,p,y','ffffffffff',
|
|
|
|
pos:x(),
|
|
|
|
pos:y(),
|
|
|
|
pos:z(),
|
|
|
|
quat:q1(),
|
|
|
|
quat:q2(),
|
|
|
|
quat:q3(),
|
|
|
|
quat:q4(),
|
|
|
|
math.deg(quat:get_euler_roll()),
|
|
|
|
math.deg(quat:get_euler_pitch()),
|
|
|
|
math.deg(quat:get_euler_yaw()))
|
|
|
|
end
|
|
|
|
|
2022-10-26 00:38:34 -03:00
|
|
|
--[[
|
|
|
|
check if a number is Nan.
|
|
|
|
--]]
|
|
|
|
function isNaN(value)
|
|
|
|
-- NaN is lua is not equal to itself
|
|
|
|
return value ~= value
|
|
|
|
end
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
local path_var = {}
|
|
|
|
path_var.count = 0
|
|
|
|
path_var.initial_ori = Quaternion()
|
|
|
|
path_var.initial_maneuver_to_earth = Quaternion()
|
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
function do_path()
|
2022-09-15 00:52:13 -03:00
|
|
|
local now = millis():tofloat() * 0.001
|
|
|
|
|
|
|
|
path_var.count = path_var.count + 1
|
|
|
|
local target_dt = 1.0/LOOP_RATE
|
2022-10-25 02:43:03 -03:00
|
|
|
local path = current_task.fn
|
|
|
|
local arg1 = current_task.args[1]
|
|
|
|
local arg2 = current_task.args[2]
|
|
|
|
local arg3 = current_task.args[3]
|
|
|
|
local arg4 = current_task.args[4]
|
|
|
|
|
|
|
|
if not current_task.started then
|
|
|
|
local initial_yaw_deg = current_task.initial_yaw_deg
|
|
|
|
current_task.started = true
|
2022-10-06 03:05:31 -03:00
|
|
|
path_var.length = path_length(path, arg1, arg2, arg3, arg4)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
path_var.total_rate_rads_ef = makeVector3f(0.0, 0.0, 0.0)
|
|
|
|
local speed = target_groundspeed()
|
|
|
|
|
|
|
|
--assuming constant velocity
|
|
|
|
path_var.total_time = path_var.length/speed
|
2022-10-06 03:05:31 -03:00
|
|
|
path_var.last_pos, last_angle = path(0.0, arg1, arg2, arg3, arg4) --position at t0
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
--deliberately only want yaw component, because the maneuver should be performed relative to the earth, not relative to the initial orientation
|
|
|
|
path_var.initial_ori:from_euler(0, 0, math.rad(initial_yaw_deg))
|
|
|
|
|
|
|
|
path_var.initial_maneuver_to_earth:from_euler(0, 0, -math.rad(initial_yaw_deg))
|
|
|
|
|
|
|
|
path_var.initial_ef_pos = ahrs:get_relative_position_NED_origin()
|
|
|
|
|
|
|
|
|
2022-10-26 00:48:24 -03:00
|
|
|
local corrected_position_t0_ef, angle_t0 = rotate_path(path, target_dt/path_var.total_time,
|
2022-10-06 03:05:31 -03:00
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
2022-10-26 00:48:24 -03:00
|
|
|
local corrected_position_t1_ef, angle_t1 = rotate_path(path, 2*target_dt/path_var.total_time,
|
2022-10-06 03:05:31 -03:00
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
path_var.start_pos = ahrs:get_position()
|
|
|
|
path_var.path_int = path_var.start_pos:copy()
|
|
|
|
|
2022-09-22 02:56:21 -03:00
|
|
|
speed_PI.reset()
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
|
|
|
|
path_var.accumulated_orientation_rel_ef = path_var.initial_ori
|
|
|
|
|
|
|
|
path_var.time_correction = 0.0
|
|
|
|
|
|
|
|
path_var.filtered_angular_velocity = Vector3f()
|
|
|
|
|
|
|
|
path_var.start_time = now + target_dt
|
|
|
|
path_var.last_time = now
|
|
|
|
path_var.average_dt = target_dt
|
|
|
|
path_var.scaled_dt = target_dt
|
|
|
|
|
|
|
|
path_var.path_t = 0
|
|
|
|
path_var.target_speed = speed
|
2022-10-06 03:05:31 -03:00
|
|
|
return true
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
|
|
|
|
|
|
|
local vel_length = ahrs:get_velocity_NED():length()
|
|
|
|
|
|
|
|
local actual_dt = now - path_var.last_time
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local local_n_dt = actual_dt/path_var.total_time
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
path_var.last_time = now
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
if path_var.path_t > 1.0 then --done
|
2022-09-22 02:56:21 -03:00
|
|
|
return false
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--[[
|
|
|
|
calculate positions and angles at previous, current and next time steps
|
|
|
|
--]]
|
2022-09-15 00:52:13 -03:00
|
|
|
|
|
|
|
next_target_pos_ef = next_target_pos_ef
|
2022-10-06 03:05:31 -03:00
|
|
|
local p0, r0 = rotate_path(path, path_var.path_t + 0*local_n_dt,
|
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
|
|
|
local p1, r1 = rotate_path(path, path_var.path_t + 1*local_n_dt,
|
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
|
|
|
local p2, r2 = rotate_path(path, path_var.path_t + 2*local_n_dt,
|
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
local current_measured_pos_ef = ahrs:get_relative_position_NED_origin()
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--[[
|
|
|
|
get tangents to the path
|
|
|
|
--]]
|
|
|
|
local tangent1_ef = p1 - p0
|
|
|
|
local tangent2_ef = p2 - p1
|
|
|
|
local tv_unit = tangent2_ef:copy()
|
|
|
|
tv_unit:normalize()
|
|
|
|
|
|
|
|
--[[
|
|
|
|
use actual vehicle velocity to calculate how far along the
|
|
|
|
path we have progressed
|
|
|
|
--]]
|
|
|
|
local v = ahrs:get_velocity_NED()
|
|
|
|
local path_dist = v:dot(tv_unit)*actual_dt
|
|
|
|
if path_dist < 0 then
|
|
|
|
gcs:send_text(0, string.format("aborting"))
|
|
|
|
return false
|
|
|
|
end
|
|
|
|
local path_t_delta = constrain(path_dist/path_var.length, 0.2*local_n_dt, 4*local_n_dt)
|
|
|
|
path_var.path_t = path_var.path_t + path_t_delta
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--[[
|
|
|
|
recalculate the current path position and angle based on actual delta time
|
|
|
|
--]]
|
|
|
|
p2, r2 = rotate_path(path, path_var.path_t + path_t_delta,
|
|
|
|
arg1, arg2, arg3, arg4,
|
|
|
|
path_var.initial_ori, path_var.initial_ef_pos)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- tangents needs to be recalculated
|
|
|
|
tangent1_ef = p1 - p0
|
|
|
|
tangent2_ef = p2 - p1
|
|
|
|
tv_unit = tangent2_ef:copy()
|
|
|
|
tv_unit:normalize()
|
2022-10-06 01:49:19 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- error in position versus current point on the path
|
|
|
|
local pos_error_ef = current_measured_pos_ef - p1
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--[[
|
|
|
|
calculate a time correction. We first get the projection of
|
|
|
|
the position error onto the track. This tells us how far we
|
|
|
|
are ahead or behind on the track
|
|
|
|
--]]
|
|
|
|
local path_dist_err_m = tv_unit:dot(pos_error_ef)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- normalize against the total path length
|
|
|
|
local path_err_t = path_dist_err_m / path_var.length
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- don't allow the path to go backwards in time, or faster than twice the actual rate
|
|
|
|
path_err_t = constrain(path_err_t, -0.9*path_t_delta, 2*path_t_delta)
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- correct time to bring us back into sync
|
|
|
|
path_var.path_t = path_var.path_t + TIME_CORR_P:get() * path_err_t
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
|
|
|
|
--[[
|
|
|
|
calculation of error correction, calculating acceleration
|
|
|
|
needed to bring us back on the path, and body rates in pitch and
|
|
|
|
yaw to achieve those accelerations
|
|
|
|
--]]
|
|
|
|
|
|
|
|
-- component of pos_err perpendicular to the current path tangent
|
|
|
|
local B = ortho_proj(pos_error_ef, tv_unit)
|
|
|
|
|
|
|
|
-- derivative of pos_err perpendicular to the current path tangent, assuming tangent is constant
|
|
|
|
local B_dot = ortho_proj(v, tv_unit)
|
|
|
|
|
|
|
|
-- gains for error correction.
|
|
|
|
local acc_err_ef = B:scale(ERR_CORR_P:get()) + B_dot:scale(ERR_CORR_D:get())
|
|
|
|
|
|
|
|
local acc_err_bf = ahrs:earth_to_body(acc_err_ef)
|
|
|
|
|
|
|
|
local TAS = constrain(ahrs:get_EAS2TAS()*ahrs:airspeed_estimate(), 3, 100)
|
|
|
|
local corr_rate_bf_y_rads = -acc_err_bf:z()/TAS
|
|
|
|
local corr_rate_bf_z_rads = acc_err_bf:y()/TAS
|
|
|
|
|
|
|
|
local cor_ang_vel_bf_rads = makeVector3f(0.0, corr_rate_bf_y_rads, corr_rate_bf_z_rads)
|
|
|
|
local cor_ang_vel_bf_dps = cor_ang_vel_bf_rads:scale(math.deg(1))
|
|
|
|
|
|
|
|
|
|
|
|
--[[
|
|
|
|
work out body frame path rate, this is based on two adjacent tangents on the path
|
|
|
|
--]]
|
|
|
|
local path_rate_ef_rads = vectors_to_angular_rate(tangent1_ef, tangent2_ef, actual_dt)
|
|
|
|
local path_rate_ef_dps = path_rate_ef_rads:scale(math.deg(1))
|
|
|
|
local path_rate_bf_dps = ahrs:earth_to_body(path_rate_ef_dps)
|
|
|
|
|
|
|
|
-- set the path roll rate
|
|
|
|
path_rate_bf_dps:x(math.deg(wrap_pi(r1 - r0)/actual_dt))
|
|
|
|
|
|
|
|
|
|
|
|
--[[
|
|
|
|
calculate body frame roll rate to achieved the desired roll
|
|
|
|
angle relative to the maneuver path
|
|
|
|
--]]
|
|
|
|
local zero_roll_angle_delta = Quaternion()
|
|
|
|
zero_roll_angle_delta:from_angular_velocity(path_rate_ef_rads, actual_dt)
|
|
|
|
|
|
|
|
path_var.accumulated_orientation_rel_ef = zero_roll_angle_delta*path_var.accumulated_orientation_rel_ef
|
|
|
|
path_var.accumulated_orientation_rel_ef:normalize()
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
local mf_axis = makeVector3f(1, 0, 0)
|
|
|
|
path_var.accumulated_orientation_rel_ef:earth_to_body(mf_axis)
|
|
|
|
|
|
|
|
local orientation_rel_mf_with_roll_angle = Quaternion()
|
2022-10-06 03:05:31 -03:00
|
|
|
orientation_rel_mf_with_roll_angle:from_axis_angle(mf_axis, r1)
|
2022-09-15 00:52:13 -03:00
|
|
|
orientation_rel_ef_with_roll_angle = orientation_rel_mf_with_roll_angle*path_var.accumulated_orientation_rel_ef
|
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
--[[
|
|
|
|
calculate the error correction for the roll versus the desired roll
|
|
|
|
--]]
|
2022-09-15 00:52:13 -03:00
|
|
|
local roll_error = orientation_rel_ef_with_roll_angle*ahrs:get_quaternion():inverse()
|
|
|
|
roll_error:normalize()
|
2022-10-06 03:05:31 -03:00
|
|
|
local err_axis_ef, err_angle_rad = to_axis_and_angle(roll_error)
|
2022-09-15 00:52:13 -03:00
|
|
|
local time_const_roll = ROLL_CORR_TC:get()
|
2022-10-06 03:05:31 -03:00
|
|
|
local err_angle_rate_ef_rads = err_axis_ef:scale(err_angle_rad/time_const_roll)
|
|
|
|
local err_angle_rate_bf_dps = ahrs:earth_to_body(err_angle_rate_ef_rads):scale(math.deg(1))
|
|
|
|
-- zero any non-roll components
|
|
|
|
err_angle_rate_bf_dps:y(0)
|
|
|
|
err_angle_rate_bf_dps:z(0)
|
|
|
|
|
|
|
|
--[[
|
|
|
|
total angular rate is sum of path rate, correction rate and roll correction rate
|
|
|
|
--]]
|
|
|
|
local tot_ang_vel_bf_dps = path_rate_bf_dps + cor_ang_vel_bf_dps + err_angle_rate_bf_dps
|
|
|
|
|
|
|
|
|
|
|
|
--[[
|
|
|
|
log POSM is pose-measured, POST is pose-track, POSB is pose-track without the roll
|
|
|
|
--]]
|
|
|
|
log_pose('POSM', current_measured_pos_ef, ahrs:get_quaternion())
|
|
|
|
log_pose('POST', p1, orientation_rel_ef_with_roll_angle)
|
|
|
|
|
|
|
|
logger.write('AETM', 'T,Terr','ff',
|
|
|
|
path_var.path_t,
|
|
|
|
path_err_t)
|
|
|
|
|
|
|
|
logger.write('AERT','Cx,Cy,Cz,Px,Py,Pz,Ex,Tx,Ty,Tz', 'ffffffffff',
|
|
|
|
cor_ang_vel_bf_dps:x(), cor_ang_vel_bf_dps:y(), cor_ang_vel_bf_dps:z(),
|
|
|
|
path_rate_bf_dps:x(), path_rate_bf_dps:y(), path_rate_bf_dps:z(),
|
|
|
|
err_angle_rate_bf_dps:x(),
|
|
|
|
tot_ang_vel_bf_dps:x(), tot_ang_vel_bf_dps:y(), tot_ang_vel_bf_dps:z())
|
|
|
|
|
|
|
|
--log_pose('POSB', p1, path_var.accumulated_orientation_rel_ef)
|
|
|
|
|
|
|
|
--[[
|
|
|
|
run the throttle based speed controller
|
|
|
|
--]]
|
2022-10-26 00:59:15 -03:00
|
|
|
throttle = speed_PI.update(path_var.target_speed)
|
2022-09-15 00:52:13 -03:00
|
|
|
throttle = constrain(throttle, 0, 100.0)
|
2022-10-06 03:05:31 -03:00
|
|
|
|
2022-10-26 00:38:34 -03:00
|
|
|
if isNaN(throttle) or isNaN(tot_ang_vel_bf_dps:x()) or isNaN(tot_ang_vel_bf_dps:y()) or isNaN(tot_ang_vel_bf_dps:z()) then
|
|
|
|
gcs:send_text(0,string.format("Path NaN - aborting"))
|
|
|
|
return false
|
|
|
|
end
|
2022-10-06 03:05:31 -03:00
|
|
|
|
|
|
|
vehicle:set_target_throttle_rate_rpy(throttle, tot_ang_vel_bf_dps:x(), tot_ang_vel_bf_dps:y(), tot_ang_vel_bf_dps:z())
|
|
|
|
|
2022-09-22 02:56:21 -03:00
|
|
|
return true
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
--[[
|
|
|
|
an object defining a path
|
|
|
|
--]]
|
|
|
|
function PathFunction(fn, name)
|
|
|
|
local self = {}
|
|
|
|
self.fn = fn
|
|
|
|
self.name = name
|
|
|
|
return self
|
|
|
|
end
|
|
|
|
|
2022-09-22 02:56:21 -03:00
|
|
|
command_table = {}
|
2022-10-25 02:43:03 -03:00
|
|
|
command_table[1] = PathFunction(figure_eight, "Figure Eight")
|
|
|
|
command_table[2] = PathFunction(loop, "Loop")
|
|
|
|
command_table[3] = PathFunction(horizontal_rectangle, "Horizontal Rectangle")
|
|
|
|
command_table[4] = PathFunction(climbing_circle, "Climbing Circle")
|
|
|
|
command_table[5] = PathFunction(vertical_aerobatic_box, "Vertical Box")
|
|
|
|
command_table[6] = PathFunction(banked_circle, "Banked Circle")
|
|
|
|
command_table[7] = PathFunction(straight_roll, "Axial Roll")
|
|
|
|
command_table[8] = PathFunction(rolling_circle, "Rolling Circle")
|
|
|
|
command_table[9] = PathFunction(half_cuban_eight, "Half Cuban Eight")
|
|
|
|
command_table[10]= PathFunction(half_reverse_cuban_eight, "Half Reverse Cuban Eight")
|
|
|
|
command_table[11]= PathFunction(cuban_eight, "Cuban Eight")
|
|
|
|
command_table[12]= PathFunction(humpty_bump, "Humpty Bump")
|
|
|
|
command_table[13]= PathFunction(straight_flight, "Straight Flight")
|
|
|
|
command_table[14]= PathFunction(scale_figure_eight, "Scale Figure Eight")
|
2022-09-22 03:41:18 -03:00
|
|
|
|
2022-10-06 03:05:31 -03:00
|
|
|
-- get a location structure from a waypoint number
|
|
|
|
function get_location(i)
|
|
|
|
local m = mission:get_item(i)
|
|
|
|
local loc = Location()
|
|
|
|
loc:lat(m:x())
|
|
|
|
loc:lng(m:y())
|
|
|
|
loc:relative_alt(true)
|
|
|
|
loc:terrain_alt(false)
|
|
|
|
loc:origin_alt(false)
|
|
|
|
loc:alt(math.floor(m:z()*100))
|
|
|
|
return loc
|
|
|
|
end
|
|
|
|
|
|
|
|
-- set wp location
|
|
|
|
function wp_setloc(wp, loc)
|
|
|
|
wp:x(loc:lat())
|
|
|
|
wp:y(loc:lng())
|
|
|
|
wp:z(loc:alt()*0.01)
|
|
|
|
end
|
|
|
|
|
|
|
|
-- add a waypoint to the end of the mission
|
|
|
|
function wp_add(loc,ctype,param1,param2)
|
|
|
|
local wp = mavlink_mission_item_int_t()
|
|
|
|
wp_setloc(wp,loc)
|
|
|
|
wp:command(ctype)
|
|
|
|
local seq = mission:num_commands()
|
|
|
|
wp:seq(seq)
|
|
|
|
wp:param1(param1)
|
|
|
|
wp:param2(param2)
|
|
|
|
wp:frame(3) -- global position, relative alt
|
|
|
|
mission:set_item(seq, wp)
|
|
|
|
end
|
|
|
|
|
|
|
|
-- add a NAV_SCRIPT_TIME waypoint to the end of the mission
|
|
|
|
function wp_add_nav_script(cmdid,arg1,arg2,arg3,arg4)
|
|
|
|
local wp = mavlink_mission_item_int_t()
|
|
|
|
wp:command(NAV_SCRIPT_TIME)
|
|
|
|
local seq = mission:num_commands()
|
|
|
|
wp:seq(seq)
|
|
|
|
wp:param1(cmdid)
|
|
|
|
wp:param2(0) -- timeout
|
|
|
|
wp:param3(arg1)
|
|
|
|
wp:param4(arg2)
|
|
|
|
wp:x(arg3)
|
|
|
|
wp:y(arg4)
|
|
|
|
mission:set_item(seq, wp)
|
|
|
|
end
|
|
|
|
|
|
|
|
--[[
|
|
|
|
create auto mission 1
|
|
|
|
--]]
|
|
|
|
function create_auto_mission1()
|
|
|
|
local N = mission:num_commands()
|
|
|
|
if N ~= 4 then
|
|
|
|
gcs:send_text(0,string.format("Auto mission needs takeoff and 2 WPs (got %u)", N))
|
|
|
|
return
|
|
|
|
end
|
|
|
|
local takeoff_m = mission:get_item(1)
|
|
|
|
if takeoff_m:command() ~= NAV_TAKEOFF then
|
|
|
|
gcs:send_text(0,string.format("First WP needs to be takeoff"))
|
|
|
|
return
|
|
|
|
end
|
|
|
|
local wp1 = get_location(2)
|
|
|
|
local wp2 = get_location(3)
|
|
|
|
|
|
|
|
local wp_dist = wp1:get_distance(wp2)
|
|
|
|
local wp_bearing = math.deg(wp1:get_bearing(wp2))
|
|
|
|
local radius = AUTO_RAD:get()
|
|
|
|
|
|
|
|
gcs:send_text(0, string.format("WP Distance %.0fm bearing %.1fdeg", wp_dist, wp_bearing))
|
|
|
|
|
|
|
|
-- find mid-point, 25% and 75% points
|
|
|
|
local wp_mid = wp1:copy()
|
|
|
|
wp_mid:offset_bearing(wp_bearing, wp_dist*0.5)
|
|
|
|
|
|
|
|
local wp_25pct = wp1:copy()
|
|
|
|
wp_25pct:offset_bearing(wp_bearing, wp_dist*0.25)
|
|
|
|
|
|
|
|
local wp_75pct = wp1:copy()
|
|
|
|
wp_75pct:offset_bearing(wp_bearing, wp_dist*0.75)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding half cuban eight")
|
|
|
|
wp_add_nav_script(9, radius, 0, 0, 0)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding loop")
|
|
|
|
wp_add(wp_mid, NAV_WAYPOINT, 0, 1)
|
|
|
|
wp_add_nav_script(2, radius, 0, 0, 0)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding half reverse cuban eight")
|
|
|
|
wp_add(wp1, NAV_WAYPOINT, 0, 0)
|
|
|
|
wp_add_nav_script(10, radius, 0, 0, 0)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding axial roll")
|
|
|
|
wp_add(wp_25pct, NAV_WAYPOINT, 0, 1)
|
|
|
|
wp_add_nav_script(7, wp_dist*0.5, 1, 0, 0)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding humpty bump")
|
|
|
|
wp_add(wp2, NAV_WAYPOINT, 0, 1)
|
|
|
|
wp_add_nav_script(12, radius*0.25, 0.5*radius, 0, 0)
|
|
|
|
|
|
|
|
gcs:send_text(0,"Adding cuban eight")
|
|
|
|
wp_add(wp_mid, NAV_WAYPOINT, 0, 0)
|
|
|
|
wp_add_nav_script(11, radius, 0, 0, 0)
|
|
|
|
|
|
|
|
wp_add(wp1, NAV_WAYPOINT, 0, 0)
|
|
|
|
|
|
|
|
end
|
|
|
|
|
|
|
|
function create_auto_mission()
|
|
|
|
if AUTO_MIS:get() == 1 then
|
|
|
|
create_auto_mission1()
|
|
|
|
else
|
|
|
|
gcs:send_text(0, string.format("Unknown auto mission", AUTO_MIS:get()))
|
|
|
|
end
|
2022-09-22 03:41:18 -03:00
|
|
|
end
|
2022-09-22 02:56:21 -03:00
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
function PathTask(fn, name, id, initial_yaw_deg, arg1, arg2, arg3, arg4)
|
|
|
|
self = {}
|
|
|
|
self.fn = fn
|
|
|
|
self.name = name
|
|
|
|
self.id = id
|
|
|
|
self.initial_yaw_deg = initial_yaw_deg
|
|
|
|
self.args = { arg1, arg2, arg3, arg4 }
|
|
|
|
self.started = false
|
|
|
|
return self
|
|
|
|
end
|
|
|
|
|
|
|
|
-- see if an auto mission item needs to be run
|
|
|
|
function check_auto_mission()
|
|
|
|
id, cmd, arg1, arg2, arg3, arg4 = vehicle:nav_script_time()
|
|
|
|
if not id then
|
|
|
|
return
|
|
|
|
end
|
|
|
|
if id ~= last_id then
|
|
|
|
-- we've started a new command
|
|
|
|
current_task = nil
|
|
|
|
last_id = id
|
2022-10-26 00:48:24 -03:00
|
|
|
local initial_yaw_deg = math.deg(ahrs:get_yaw())
|
2022-10-25 02:43:03 -03:00
|
|
|
gcs:send_text(0, string.format("Starting %s!", command_table[cmd].name ))
|
|
|
|
|
|
|
|
-- work out yaw between previous WP and next WP
|
|
|
|
local cnum = mission:get_current_nav_index()
|
|
|
|
-- find previous nav waypoint
|
|
|
|
local loc_prev = get_wp_location(cnum-1)
|
|
|
|
local loc_next = get_wp_location(cnum+1)
|
|
|
|
local i= cnum-1
|
|
|
|
while get_wp_location(i):lat() == 0 and get_wp_location(i):lng() == 0 do
|
|
|
|
i = i-1
|
|
|
|
loc_prev = get_wp_location(i)
|
|
|
|
end
|
|
|
|
-- find next nav waypoint
|
|
|
|
i = cnum+1
|
|
|
|
while get_wp_location(i):lat() == 0 and get_wp_location(i):lng() == 0 do
|
|
|
|
i = i+1
|
|
|
|
loc_next = get_wp_location(resolve_jump(i))
|
|
|
|
end
|
2022-10-26 00:48:24 -03:00
|
|
|
local wp_yaw_deg = math.deg(loc_prev:get_bearing(loc_next))
|
2022-10-25 02:43:03 -03:00
|
|
|
if math.abs(wrap_180(initial_yaw_deg - wp_yaw_deg)) > 90 then
|
|
|
|
gcs:send_text(0, string.format("Doing turnaround!"))
|
|
|
|
wp_yaw_deg = wrap_180(wp_yaw_deg + 180)
|
|
|
|
end
|
|
|
|
initial_yaw_deg = wp_yaw_deg
|
|
|
|
current_task = PathTask(command_table[cmd].fn, command_table[cmd].name,
|
|
|
|
id, initial_yaw_deg, arg1, arg2, arg3, arg4)
|
|
|
|
end
|
|
|
|
end
|
|
|
|
|
|
|
|
local last_trick_action_state = 0
|
|
|
|
local trick_sel_chan = nil
|
|
|
|
local last_trick_selection = nil
|
|
|
|
|
|
|
|
--[[
|
|
|
|
get selected trick. Trick numbers are 1 .. TRIK_COUNT. A value of 0 is invalid
|
|
|
|
--]]
|
|
|
|
function get_trick_selection()
|
|
|
|
if trick_sel_chan == nil then
|
|
|
|
trick_sel_chan = rc:find_channel_for_option(TRIK_SEL_FN:get())
|
|
|
|
if trick_sel_chan == nil then
|
|
|
|
return 0
|
|
|
|
end
|
|
|
|
end
|
|
|
|
-- get trick selection based on selection channel input and number of tricks
|
|
|
|
local i = math.floor(TRIK_COUNT:get() * constrain(0.5*(trick_sel_chan:norm_input_ignore_trim()+1),0,0.999)+1)
|
|
|
|
if TRICKS[i] == nil then
|
|
|
|
return 0
|
|
|
|
end
|
|
|
|
return i
|
|
|
|
end
|
|
|
|
|
|
|
|
--[[
|
|
|
|
check for running a trick
|
|
|
|
--]]
|
|
|
|
function check_trick()
|
|
|
|
local selection = get_trick_selection()
|
|
|
|
local action = rc:get_aux_cached(TRIK_ACT_FN:get())
|
|
|
|
if action == 0 and current_task ~= nil then
|
|
|
|
gcs:send_text(0,string.format("Trick aborted"))
|
|
|
|
current_task = nil
|
|
|
|
last_trick_selection = nil
|
|
|
|
-- use invalid mode to disable script control
|
|
|
|
vehicle:nav_scripting_enable(255)
|
|
|
|
return
|
|
|
|
end
|
|
|
|
if selection == 0 then
|
|
|
|
return
|
|
|
|
end
|
|
|
|
if action == 1 and selection ~= last_trick_selection then
|
|
|
|
local id = TRICKS[selection].id:get()
|
|
|
|
if command_table[id] ~= nil then
|
|
|
|
local cmd = command_table[id]
|
|
|
|
gcs:send_text(0, string.format("Trick %u selected (%s)", selection, cmd.name))
|
|
|
|
last_trick_selection = selection
|
|
|
|
return
|
|
|
|
end
|
|
|
|
end
|
|
|
|
if current_task ~= nil then
|
|
|
|
-- let the task finish
|
|
|
|
return
|
|
|
|
end
|
|
|
|
if action ~= last_trick_action_state then
|
|
|
|
last_trick_selection = selection
|
|
|
|
last_trick_action_state = action
|
|
|
|
if selection == 0 then
|
|
|
|
gcs:send_text(0, string.format("No trick selected"))
|
|
|
|
return
|
|
|
|
end
|
|
|
|
local id = TRICKS[selection].id:get()
|
|
|
|
if command_table[id] == nil then
|
|
|
|
gcs:send_text(0, string.format("Invalid trick ID %u", id))
|
|
|
|
return
|
|
|
|
end
|
|
|
|
local cmd = command_table[id]
|
|
|
|
if action == 1 then
|
|
|
|
gcs:send_text(0, string.format("Trick %u selected (%s)", selection, cmd.name))
|
|
|
|
end
|
|
|
|
if action == 2 then
|
|
|
|
last_trick_selection = nil
|
|
|
|
local current_mode = vehicle:get_mode()
|
|
|
|
if not vehicle:nav_scripting_enable(current_mode) then
|
|
|
|
gcs:send_text(0, string.format("Tricks not available in mode"))
|
|
|
|
return
|
|
|
|
end
|
|
|
|
gcs:send_text(0, string.format("Trick %u started (%s)", selection, cmd.name))
|
|
|
|
local initial_yaw_deg = math.deg(ahrs:get_yaw())
|
|
|
|
current_task = PathTask(cmd.fn,
|
|
|
|
cmd.name,
|
|
|
|
nil,
|
|
|
|
initial_yaw_deg,
|
|
|
|
TRICKS[selection].args[1]:get(),
|
|
|
|
TRICKS[selection].args[2]:get(),
|
|
|
|
TRICKS[selection].args[3]:get(),
|
|
|
|
TRICKS[selection].args[4]:get())
|
|
|
|
end
|
|
|
|
end
|
|
|
|
|
|
|
|
end
|
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
function update()
|
2022-10-06 03:05:31 -03:00
|
|
|
|
|
|
|
-- check if we should create a mission
|
|
|
|
if AUTO_MIS:get() > 0 then
|
|
|
|
create_auto_mission()
|
|
|
|
AUTO_MIS:set_and_save(0)
|
|
|
|
end
|
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
check_auto_mission()
|
|
|
|
if TRICKS ~= nil and vehicle:get_mode() ~= MODE_AUTO then
|
|
|
|
check_trick()
|
|
|
|
end
|
2022-09-15 00:52:13 -03:00
|
|
|
|
2022-10-25 02:43:03 -03:00
|
|
|
if current_task ~= nil then
|
|
|
|
if not do_path() then
|
|
|
|
gcs:send_text(0, string.format("Finishing %s!", current_task.name))
|
|
|
|
if current_task.id ~= nil then
|
|
|
|
vehicle:nav_script_time_done(current_task.id)
|
|
|
|
else
|
|
|
|
-- use invalid mode to disable script control
|
|
|
|
vehicle:nav_scripting_enable(255)
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
2022-10-25 02:43:03 -03:00
|
|
|
current_task = nil
|
2022-09-15 00:52:13 -03:00
|
|
|
end
|
|
|
|
end
|
2022-10-25 02:43:03 -03:00
|
|
|
|
2022-09-15 00:52:13 -03:00
|
|
|
return update, 1000.0/LOOP_RATE
|
|
|
|
end
|
|
|
|
|
|
|
|
return update()
|