AP_Scripting: examaples move to : acsess

This commit is contained in:
Iampete1 2022-09-03 17:02:38 +01:00 committed by Andrew Tridgell
parent 5b2236e88c
commit 60a75a0973
14 changed files with 22 additions and 22 deletions

View File

@ -320,7 +320,7 @@ function update_slew_gain()
local ax_stage = string.sub(slew_parm, -1)
adjust_gain(slew_parm, P:get()+slew_delta)
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
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f", slew_parm, P:get()))
slew_parm = nil
@ -459,7 +459,7 @@ function update()
adjust_gain(P_name, new_P)
end
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))
advance_stage(axis)
last_stage_change = get_time()
@ -469,7 +469,7 @@ function update()
new_gain = 0.001
end
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
last_gain_report = get_time()
gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f sr:%.2f", pname, new_gain, srate))

View File

@ -164,7 +164,7 @@ local function PI_controller(kP,kI,iMax)
-- 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)
logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total)
end
-- return the instance
return self

View File

@ -139,7 +139,7 @@ local function PI_controller(kP,kI,iMax)
-- 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)
logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total)
end
-- return the instance
return self

View File

@ -104,7 +104,7 @@ local function PI_controller(kP,kI,iMax)
-- 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)
logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total)
end
-- return the instance
return self

View File

@ -2,7 +2,7 @@
-- https://os.mbed.com/users/benkatz/code/HKC_MiniCheetah/docs/tip/CAN__com_8cpp_source.html
-- Load CAN driver with a buffer size of 20
local driver = CAN.get_device(20)
local driver = CAN:get_device(20)
local target_ID = uint32_t(1)

View File

@ -2,8 +2,8 @@
-- Load CAN driver1. The first will attach to a protocol of 10, the 2nd to a protocol of 12
-- this allows the script to distinguish packets on two CAN interfaces
local driver1 = CAN.get_device(5)
local driver2 = CAN.get_device2(5)
local driver1 = CAN:get_device(5)
local driver2 = CAN:get_device2(5)
if not driver1 and not driver2 then
gcs:send_text(0,"No scripting CAN interfaces found")

View File

@ -1,7 +1,7 @@
-- This script is an example of writing to CAN bus
-- Load CAN driver, using the scripting protocol and with a buffer size of 5
local driver = CAN.get_device(5)
local driver = CAN:get_device(5)
-- transfer ID of the message were sending
local Transfer_ID = 0

View File

@ -57,7 +57,7 @@ local function PIFF(kFF,kP,kI,iMax)
-- log the controller internals
function self.log(name)
logger.write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(_log_data))
logger:write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(_log_data))
end
-- return the instance
@ -110,7 +110,7 @@ function PIFF2.update(self, target, current)
end
function PIFF2.log(self, name)
logger.write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(self.log_data))
logger:write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(self.log_data))
end
--[[

View File

@ -28,7 +28,7 @@ file:write('Lattitude (°), Longitude (°), Absolute Altitude (m), PM 1.0, PM 2.
file:close()
-- load the i2c driver, bus 0
local sensor = i2c.get_device(0,0x33)
local sensor = i2c:get_device(0,0x33)
sensor:set_retries(10)
-- register names
@ -173,7 +173,7 @@ function update() -- this is the loop which periodically runs
file:close()
-- save to data flash
logger.write('PART','PM1,PM2.5,PM10,Cnt0.5,Cnt1,Cnt2.5,Cnt5,Cnt7.5,Cnt10','fffffffff',PM1_0,PM2_5,PM10,PC0_5,PC1_0,PC2_5,PC5_0,PC7_5,PC10)
logger:write('PART','PM1,PM2.5,PM10,Cnt0.5,Cnt1,Cnt2.5,Cnt5,Cnt7.5,Cnt10','fffffffff',PM1_0,PM2_5,PM10,PC0_5,PC1_0,PC2_5,PC5_0,PC7_5,PC10)
-- send to GCS
gcs:send_named_float('PM 1.0',PM1_0)

View File

@ -100,7 +100,7 @@ function update()
-- format characters specify the type of variable to be logged, see AP_Logger/README.md
-- not all format types are supported by scripting only: i, L, e, f, n, M, B, I, E, N, and Z
-- Note that Lua automatically adds a timestamp in micro seconds
logger.write('SCR','Sensor1, Sensor2, Sensor3','fff',table.unpack(log_data))
logger:write('SCR','Sensor1, Sensor2, Sensor3','fff',table.unpack(log_data))
-- reset for the next message
log_data = {}

View File

@ -2,7 +2,7 @@
local address = 0
local found = 0
local i2c_bus = i2c.get_device(0,0)
local i2c_bus = i2c:get_device(0,0)
i2c_bus:set_retries(10)
function update() -- this is the loop which periodically runs

View File

@ -30,10 +30,10 @@ local function write_to_dataflash()
-- https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_Logger
-- not all format types are supported by scripting only: i, L, e, f, n, M, B, I, E, and N
-- lua automatically adds a timestamp in micro seconds
logger.write('SCR1','roll(deg),pitch(deg),yaw(deg)','fff',interesting_data[roll],interesting_data[pitch],interesting_data[yaw])
logger:write('SCR1','roll(deg),pitch(deg),yaw(deg)','fff',interesting_data[roll],interesting_data[pitch],interesting_data[yaw])
-- it is also possible to give units and multipliers
logger.write('SCR2','roll,pitch,yaw','fff','ddd','---',interesting_data[roll],interesting_data[pitch],interesting_data[yaw])
logger:write('SCR2','roll,pitch,yaw','fff','ddd','---',interesting_data[roll],interesting_data[pitch],interesting_data[yaw])
end

View File

@ -244,7 +244,7 @@ function track_return_time()
end
end
logger.write('SFSC','total_return_time,remaining_return_time','If','ss','--',total_time,return_time)
logger:write('SFSC','total_return_time,remaining_return_time','If','ss','--',total_time,return_time)
end
return track_return_time, 100
end
@ -332,7 +332,7 @@ function update()
return_q = 0.5 * density * return_airspeed^2 -- we could estimate the change in density also, but will be negligible
end
logger.write('SFSA','return_time,return_airspeed,Q,return_Q','ffff','snPP','----',return_time,return_airspeed,q,return_q)
logger:write('SFSA','return_time,return_airspeed,Q,return_Q','ffff','snPP','----',return_time,return_airspeed,q,return_q)
for i = 1, #batt_info do
local instance, norm_filtered_amps, rated_capacity_mah = table.unpack(batt_info[i])
@ -354,7 +354,7 @@ function update()
local remaining_time = remaining_capacity / return_amps
local buffer_time = remaining_time - ((return_time * time_SF) + margin)
logger.write('SFSB','Instance,current,rem_cap,rem_time,buffer','Bffff','#Aiss','--C--',i-1,return_amps,remaining_capacity,remaining_time,buffer_time)
logger:write('SFSB','Instance,current,rem_cap,rem_time,buffer','Bffff','#Aiss','--C--',i-1,return_amps,remaining_capacity,remaining_time,buffer_time)
if (return_time < 0) or buffer_time < 0 then
if return_time < 0 then
gcs:send_text(0, "Failsafe: ground speed low can not get home")

View File

@ -253,7 +253,7 @@ function check_approach_tangent()
local holdoff_dist = get_holdoff_distance()
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())))
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
distance < 2.5*holdoff_dist and
distance > 0.7*holdoff_dist and