AP_Scripting: ESC_slew_rate: fix lua warning

Docs say that logger must be called with `:`.
This commit is contained in:
Thomas Watson 2024-10-31 19:59:33 -05:00 committed by Peter Hall
parent 3764f377d8
commit 195d3b78e6
1 changed files with 1 additions and 1 deletions

View File

@ -44,7 +44,7 @@ function update()
local pwm_mid = 0.5*(pwm_min+pwm_max)
local pwm = math.floor(pwm_mid + (pwm_max-pwm_mid) * output)
SRV_Channels:set_output_pwm_chan_timeout(chan-1, pwm, 100)
logger.write('ESLW', 'PWM,Freq', 'If', pwm, freq)
logger:write('ESLW', 'PWM,Freq', 'If', pwm, freq)
gcs:send_named_float('PWN',pwm)
gcs:send_named_float('FREQ',freq)
end