Skip to content

Commit 01ade70

Browse files
committed
proper chirp
1 parent 34a15e4 commit 01ade70

File tree

1 file changed

+8
-8
lines changed

1 file changed

+8
-8
lines changed

libraries/AP_Scripting/examples/plane-sweep.lua

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@ local SWEEP_ACTION_CHANNEL = 6 -- RCIN channel to start a SWEEP when high (>1700
1212
local SWEEP_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high)
1313
local SWEEP_FUCNTION = 1 -- which control surface (SERVOx_FUNCTION) number will have a SWEEP happen
1414
-- 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
1616
local SWEEP_TIME = 120000 -- period of SWEEP signal in ms
1717
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
1919
local k = (end_freqeuncy-start_freq)/SWEEP_TIME -- rate of change of frequency in sweep
2020
local t_i = 0
2121
local amplitude_sent = 0
@@ -42,7 +42,8 @@ local input = 9
4242
local start_freq_rads = 2 * math.pi * start_freq
4343
local end_freq_rads = 2 * math.pi * end_freqeuncy
4444
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
4647

4748

4849
local interesting_data = {}
@@ -74,7 +75,6 @@ local function write_to_dataflash()
7475
function SWEEP(pre_SWEEP_elevator, pre_SWEEP_aileron, pre_SWEEP_rudder, pre_SWEEP_throttle)
7576
local now = millis()
7677
local SWEEP_choice_pwm = rc:get_pwm(SWEEP_CHOICE_CHANNEL)
77-
local callback_time = 10
7878
if rc:get_pwm(SWEEP_ACTION_CHANNEL) < 1700 then
7979
pre_SWEEP_elevator = SRV_Channels:get_output_pwm(K_ELEVATOR)
8080
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
121121
if start_time == -1 then
122122
start_time = now
123123
gcs:send_text(6, "STARTING SWEEP " .. SWEEP_srv_chan)
124-
retry_set_mode(MODE_MANUAL)
124+
retry_set_mode(MODE_FBWA)
125125
end
126126
if now < (start_time + (SWEEP_TIME)) then
127127
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
129129
amplitude_sent = SWEEP_MAGNITUDE*math.sin(tonumber(2*math.pi*(start_freq * t_i + (k / 2) * t_i*t_i)))
130130
-- amplitude_sent = SWEEP_MAGNITUDE * math.sin(start_freq_rads * (math.exp(k * t_i) - 1) / k)
131131
amplitude_sent = math.floor(amplitude_sent)
@@ -144,7 +144,7 @@ function SWEEP(pre_SWEEP_elevator, pre_SWEEP_aileron, pre_SWEEP_rudder, pre_SWEE
144144
interesting_data[acc_y] = acc:y()
145145
interesting_data[acc_z] = acc:z()
146146
interesting_data[RcOut] = op
147-
interesting_data[t_log] = t_i/1000
147+
interesting_data[t_log] = t_i
148148
interesting_data[input] = amplitude_sent
149149
write_to_dataflash()
150150
else
@@ -173,4 +173,4 @@ local pre_SWEEP_elevator = SRV_Channels:get_output_pwm(K_ELEVATOR)
173173
local pre_SWEEP_aileron = SRV_Channels:get_output_pwm(K_AILERON)
174174
local pre_SWEEP_rudder = SRV_Channels:get_output_pwm(K_RUDDER)
175175
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

Comments
 (0)