Hi all. Pixhawk 6x, ArduPlane 4.5.7. I’ve noticed latency in the lua script of mine, sometimes I can see a 50 ms and sometimes ~1 sec latency in debug messages between nil pwm value and value I set in set_output_pwm. This latency randomly changes when rebooting pixhawk. Is this latency in get_output_pwm function or real latency between executing command and setting servo pwm? Script example and screenshots of latency in messages are attached.
local PARACHUTE_SCRIPTING_CHANNEL = 109;
local PARACHUTE_SERVO_CHANNEL = 27;
local time_to_set_servo = 10000; --milliseconds
local timeout = 0;
local PARACHUTE_PWM_PARAMETER = Parameter();
PARACHUTE_PWM_PARAMETER:init("CHUTE_SERVO_ON");
local servo_parachute_release_pwm = PARACHUTE_PWM_PARAMETER:get();
local curr_time = 0;
local MAX_SERVO_NUMBER = 16;
local TEMP_PARAMETER = Parameter();
local PARACHUTE_SERVO = Parameter();
local function_complete = 0;
local PWM_message = 0
----------------------------------------------------------------------
function update()
curr_time = millis();
setServo();
return update, 50
end
----------------------------------------------------------------------
function setServo()
if (timeout == 0) then
timeout = curr_time;
end
if (curr_time - timeout >= time_to_set_servo and function_complete == 0) then
PARACHUTE_SERVO:set(PARACHUTE_SCRIPTING_CHANNEL);
gcs:send_text(7, tostring(millis()) .. " attempt to set servo channel to scripting");
if (PARACHUTE_SERVO:get() == PARACHUTE_SCRIPTING_CHANNEL) then
gcs:send_text(7, tostring(millis()) .. " servo channel set to scripting");
end
timeout = curr_time;
end
if (PARACHUTE_SERVO:get() == PARACHUTE_SCRIPTING_CHANNEL) then
SRV_Channels:set_output_pwm(PARACHUTE_SCRIPTING_CHANNEL, servo_parachute_release_pwm);
if (SRV_Channels:get_output_pwm(PARACHUTE_SCRIPTING_CHANNEL) ~= nil and PWM_message == 0) then
gcs:send_text(7, tostring(millis()) .. " Parachute servo PWM set to " .. tostring(SRV_Channels:get_output_pwm(PARACHUTE_SCRIPTING_CHANNEL)));
PWM_message = 1;
end
if (SRV_Channels:get_output_pwm(PARACHUTE_SCRIPTING_CHANNEL) == nil) then
gcs:send_text(7, tostring(millis()) .. " Parachute servo PWM is nil ")
end
function_complete = 1;
timeout = 0;
end
end
----------------------------------------------------------------------
for i = 1, MAX_SERVO_NUMBER do
TEMP_PARAMETER:init('SERVO' .. tostring(i) .. '_FUNCTION' );
if (TEMP_PARAMETER:get() == PARACHUTE_SERVO_CHANNEL) then
PARACHUTE_SERVO:init('SERVO' .. tostring(i) .. '_FUNCTION');
end
end
return update, 1000