mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Scripting: revert logger acsess changes for applets
This commit is contained in:
parent
954ade3437
commit
7700e60261
@ -320,7 +320,7 @@ function update_slew_gain()
|
|||||||
local ax_stage = string.sub(slew_parm, -1)
|
local ax_stage = string.sub(slew_parm, -1)
|
||||||
adjust_gain(slew_parm, P:get()+slew_delta)
|
adjust_gain(slew_parm, P:get()+slew_delta)
|
||||||
slew_steps = slew_steps - 1
|
slew_steps = slew_steps - 1
|
||||||
logger:write('QUIK','SRate,Gain,Param', 'ffn', get_slew_rate(axis), P:get(), axis .. ax_stage)
|
logger.write('QUIK','SRate,Gain,Param', 'ffn', get_slew_rate(axis), P:get(), axis .. ax_stage)
|
||||||
if slew_steps == 0 then
|
if slew_steps == 0 then
|
||||||
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f", slew_parm, P:get()))
|
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f", slew_parm, P:get()))
|
||||||
slew_parm = nil
|
slew_parm = nil
|
||||||
@ -459,7 +459,7 @@ function update()
|
|||||||
adjust_gain(P_name, new_P)
|
adjust_gain(P_name, new_P)
|
||||||
end
|
end
|
||||||
setup_slew_gain(pname, new_gain)
|
setup_slew_gain(pname, new_gain)
|
||||||
logger:write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage)
|
logger.write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage)
|
||||||
gcs:send_text(6, string.format("Tuning: %s done", pname))
|
gcs:send_text(6, string.format("Tuning: %s done", pname))
|
||||||
advance_stage(axis)
|
advance_stage(axis)
|
||||||
last_stage_change = get_time()
|
last_stage_change = get_time()
|
||||||
@ -469,7 +469,7 @@ function update()
|
|||||||
new_gain = 0.001
|
new_gain = 0.001
|
||||||
end
|
end
|
||||||
adjust_gain(pname, new_gain)
|
adjust_gain(pname, new_gain)
|
||||||
logger:write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage)
|
logger.write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage)
|
||||||
if get_time() - last_gain_report > 3 then
|
if get_time() - last_gain_report > 3 then
|
||||||
last_gain_report = get_time()
|
last_gain_report = get_time()
|
||||||
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f sr:%.2f", pname, new_gain, srate))
|
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f sr:%.2f", pname, new_gain, srate))
|
||||||
|
@ -253,7 +253,7 @@ function check_approach_tangent()
|
|||||||
local holdoff_dist = get_holdoff_distance()
|
local holdoff_dist = get_holdoff_distance()
|
||||||
local error1 = math.abs(wrap_180(target_bearing_deg - ground_bearing_deg))
|
local error1 = math.abs(wrap_180(target_bearing_deg - ground_bearing_deg))
|
||||||
local error2 = math.abs(wrap_180(ground_bearing_deg - (target_heading + SHIP_LAND_ANGLE:get())))
|
local error2 = math.abs(wrap_180(ground_bearing_deg - (target_heading + SHIP_LAND_ANGLE:get())))
|
||||||
logger:write('SLND','TBrg,GBrg,Dist,HDist,Err1,Err2','ffffff',target_bearing_deg, ground_bearing_deg, distance, holdoff_dist, error1, error2)
|
logger.write('SLND','TBrg,GBrg,Dist,HDist,Err1,Err2','ffffff',target_bearing_deg, ground_bearing_deg, distance, holdoff_dist, error1, error2)
|
||||||
if (error1 < margin and
|
if (error1 < margin and
|
||||||
distance < 2.5*holdoff_dist and
|
distance < 2.5*holdoff_dist and
|
||||||
distance > 0.7*holdoff_dist and
|
distance > 0.7*holdoff_dist and
|
||||||
|
Loading…
Reference in New Issue
Block a user