@ -244,7 +244,7 @@ function track_return_time()
@@ -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()
@@ -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()
@@ -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 " )