mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: review fixes
This commit is contained in:
parent
cc9b9813cb
commit
ba57e0a9d8
|
@ -1321,10 +1321,10 @@ function vehicle:set_target_posvel_NED(target_pos, target_vel) end
|
|||
function vehicle:set_target_pos_NED(target_pos, use_yaw, yaw_deg, use_yaw_rate, yaw_rate_degs, yaw_relative, terrain_alt) end
|
||||
|
||||
-- desc
|
||||
---@param param1 Location_ud -- current target
|
||||
---@param param2 Location_ud -- new target
|
||||
---@param current_target Location_ud -- current target, from get_target_location()
|
||||
---@param new_target Location_ud -- new target
|
||||
---@return boolean
|
||||
function vehicle:update_target_location(param1, param2) end
|
||||
function vehicle:update_target_location(current_target, new_target) end
|
||||
|
||||
-- desc
|
||||
---@return Location_ud|nil
|
||||
|
|
|
@ -78,27 +78,20 @@ function sq(v)
|
|||
return v*v
|
||||
end
|
||||
|
||||
-- return time since boot in seconds
|
||||
function time_seconds()
|
||||
return millis():tofloat() * 0.001
|
||||
end
|
||||
|
||||
--[[
|
||||
parameter values which are auto-set on startup
|
||||
--]]
|
||||
local key_params = {
|
||||
FOLL_ENABLE = 1,
|
||||
FOLL_OFS_TYPE = 1,
|
||||
FOLL_ALT_TYPE = 0,
|
||||
}
|
||||
|
||||
-- check key parameters
|
||||
function check_parameters()
|
||||
--[[
|
||||
parameter values which are auto-set on startup
|
||||
--]]
|
||||
local key_params = {
|
||||
FOLL_ENABLE = 1,
|
||||
FOLL_OFS_TYPE = 1,
|
||||
FOLL_ALT_TYPE = 0,
|
||||
}
|
||||
|
||||
for p, v in pairs(key_params) do
|
||||
local current = param:get(p)
|
||||
if not current then
|
||||
gcs:send_text(0,string.format("Parameter %s not found", p))
|
||||
end
|
||||
assert(current, string.format("Parameter %s not found", p))
|
||||
if math.abs(v-current) > 0.001 then
|
||||
param:set_and_save(p, v)
|
||||
gcs:send_text(0,string.format("Parameter %s set to %.2f was %.2f", p, v, current))
|
||||
|
@ -435,5 +428,20 @@ end
|
|||
|
||||
check_parameters()
|
||||
|
||||
-- wrapper around update(). This calls update() at 20Hz,
|
||||
-- and if update faults then an error is displayed, but the script is not
|
||||
-- stopped
|
||||
function protected_wrapper()
|
||||
local success, err = pcall(update)
|
||||
if not success then
|
||||
gcs:send_text(0, "Internal Error: " .. err)
|
||||
-- when we fault we run the update function again after 1s, slowing it
|
||||
-- down a bit so we don't flood the console with errors
|
||||
return protected_wrapper, 1000
|
||||
end
|
||||
return protected_wrapper, 50
|
||||
end
|
||||
|
||||
-- start running update loop
|
||||
return loop()
|
||||
return protected_wrapper()
|
||||
|
||||
|
|
|
@ -493,7 +493,7 @@ singleton AP::fwversion() field patch uint8_t read
|
|||
singleton AP::fwversion() field fw_hash_str string read
|
||||
singleton AP::fwversion() field fw_hash_str alias hash
|
||||
|
||||
include AP_Follow/AP_Follow.h
|
||||
include AP_Follow/AP_Follow.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AP_Follow depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AP_Follow alias follow
|
||||
singleton AP_Follow method have_target boolean
|
||||
|
|
Loading…
Reference in New Issue