@@ -12,10 +12,10 @@ local SWEEP_ACTION_CHANNEL = 6 -- RCIN channel to start a SWEEP when high (>1700
12
12
local SWEEP_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high)
13
13
local SWEEP_FUCNTION = 1 -- which control surface (SERVOx_FUNCTION) number will have a SWEEP happen
14
14
-- A (Servo 1, Function 4), E (Servo 2, Function 19), and R (Servo 4, Function 21)
15
- local SWEEP_MAGNITUDE = 200 -- defined out of 45 deg used for set_output_scaled
15
+ local SWEEP_MAGNITUDE = 50 -- defined out of 45 deg used for set_output_scaled
16
16
local SWEEP_TIME = 120000 -- period of SWEEP signal in ms
17
17
local start_freq = 0.05 -- start freqeuncy in hz
18
- local end_freqeuncy = 5 -- end freqeuncy in Hz
18
+ local end_freqeuncy = 5.00 -- end freqeuncy in Hz
19
19
local k = (end_freqeuncy - start_freq )/ SWEEP_TIME -- rate of change of frequency in sweep
20
20
local t_i = 0
21
21
local amplitude_sent = 0
@@ -42,7 +42,8 @@ local input = 9
42
42
local start_freq_rads = 2 * math.pi * start_freq
43
43
local end_freq_rads = 2 * math.pi * end_freqeuncy
44
44
local B = math.log (end_freq_rads / start_freq_rads )
45
- local k = B / SWEEP_TIME
45
+ local k = (end_freqeuncy - start_freq )* 1000 / SWEEP_TIME
46
+ local callback_time = 40
46
47
47
48
48
49
local interesting_data = {}
@@ -74,7 +75,6 @@ local function write_to_dataflash()
74
75
function SWEEP (pre_SWEEP_elevator , pre_SWEEP_aileron , pre_SWEEP_rudder , pre_SWEEP_throttle )
75
76
local now = millis ()
76
77
local SWEEP_choice_pwm = rc :get_pwm (SWEEP_CHOICE_CHANNEL )
77
- local callback_time = 10
78
78
if rc :get_pwm (SWEEP_ACTION_CHANNEL ) < 1700 then
79
79
pre_SWEEP_elevator = SRV_Channels :get_output_pwm (K_ELEVATOR )
80
80
pre_SWEEP_aileron = SRV_Channels :get_output_pwm (K_AILERON )
@@ -121,11 +121,11 @@ function SWEEP(pre_SWEEP_elevator, pre_SWEEP_aileron, pre_SWEEP_rudder, pre_SWEE
121
121
if start_time == - 1 then
122
122
start_time = now
123
123
gcs :send_text (6 , " STARTING SWEEP " .. SWEEP_srv_chan )
124
- retry_set_mode (MODE_MANUAL )
124
+ retry_set_mode (MODE_FBWA )
125
125
end
126
126
if now < (start_time + (SWEEP_TIME )) then
127
127
gcs :send_text (6 , " in sweep loop" .. SWEEP_srv_chan )
128
- t_i = tonumber (tostring (now - start_time ))
128
+ t_i = tonumber (tostring (now - start_time ))/ 1000
129
129
amplitude_sent = SWEEP_MAGNITUDE * math.sin (tonumber (2 * math.pi * (start_freq * t_i + (k / 2 ) * t_i * t_i )))
130
130
-- amplitude_sent = SWEEP_MAGNITUDE * math.sin(start_freq_rads * (math.exp(k * t_i) - 1) / k)
131
131
amplitude_sent = math.floor (amplitude_sent )
@@ -144,7 +144,7 @@ function SWEEP(pre_SWEEP_elevator, pre_SWEEP_aileron, pre_SWEEP_rudder, pre_SWEE
144
144
interesting_data [acc_y ] = acc :y ()
145
145
interesting_data [acc_z ] = acc :z ()
146
146
interesting_data [RcOut ] = op
147
- interesting_data [t_log ] = t_i / 1000
147
+ interesting_data [t_log ] = t_i
148
148
interesting_data [input ] = amplitude_sent
149
149
write_to_dataflash ()
150
150
else
@@ -173,4 +173,4 @@ local pre_SWEEP_elevator = SRV_Channels:get_output_pwm(K_ELEVATOR)
173
173
local pre_SWEEP_aileron = SRV_Channels :get_output_pwm (K_AILERON )
174
174
local pre_SWEEP_rudder = SRV_Channels :get_output_pwm (K_RUDDER )
175
175
local pre_SWEEP_throttle = SRV_Channels :get_output_pwm (K_THROTTLE )
176
- return SWEEP (pre_SWEEP_elevator , pre_SWEEP_aileron , pre_SWEEP_rudder , pre_SWEEP_throttle ), 40
176
+ return SWEEP (pre_SWEEP_elevator , pre_SWEEP_aileron , pre_SWEEP_rudder , pre_SWEEP_throttle ), callback_time
0 commit comments