Rpm sensor based on lua

Dear Ardupilot community, hello!

I am currently using a Notch Filter based on an RPM sensor, which has largely solved my problem - I have 48-inch props! However, my copter has 8 motors, and when my drone is moving, the motor speeds are definitely not equal, but I only detect the speed of one motor!

My ESC and motor were sold together, they are very expensive and I cannot consider replacing them. I have currently made an RPM collector that collects the speed of 8 speed sensors and sends it to the FC via serial port at 100Hz.

But I encountered difficulties in Lua. My RPM collector continuously sends the measured speed, but I don’t know how to use Lua to read it! This is too different from C#, I have no clue.

The protocol output by my RPM collector is like this: first send FFFFFFFF as the packet header, then send the low 8 bits and high 8 bits of 8 motors in turn, and repeat sending at a frequency of 100Hz and 115200bps.

his is the program I tried to write.

– Define serial port
local port = assert(serial:find_serial(0),“Could not find scripting serial port!”)
port:begin(115200)
port:set_flow_control(0)

– Define packet header
local header = “\xFF\xFF\xFF\xFF”

– Define the number of motors
local num_motors = 8

– Define the time when the last valid data was received
local last_valid_data_time = millis()

– Define a function to read and parse serial data
function read_data()
local delay = 12 – Default delay of 12 milliseconds
– Check if there is at least 20 bytes of available data
if port:available() >= 20 then
– Read data from the serial port
local data = port:read()
– Find the packet header
local start_index = string.find(data, “\xFF\xFF\xFF\xFF”)
if start_index then
– Check if there is enough data in the buffer
if string.len(data) - start_index + 1 >= 20 then
– Extract the packet
data = string.sub(data, start_index, start_index + 20 - 1)
– Update the time when the last valid data was received
last_valid_data_time = millis()
– Extract motor speed data
local motor_speeds = {}
for i = 1, num_motors do
local low_byte = string.byte(data, 4 + (i - 1) * 2)
local high_byte = string.byte(data, 5 + (i - 1) * 2)
motor_speeds[i] = low_byte + high_byte * 256
end
– Update esc*_rpm values
for i = 1, num_motors do
esc_telem:update_rpm(i - 1, motor_speeds[i], 0)

            end
            delay = 10 -- If a packet was successfully processed, delay for 10 milliseconds
        end
    end
end

-- Check if no valid data has been received for more than 1 second
if millis() - last_valid_data_time > 1000 then
    -- Send warning text to ground station
    gcs:send_text(4, "no_rpm_data")
    last_valid_data_time = millis()
end

return read_data, delay

end

return read_data, 10

I tried to debug this program. After adding else gcs:send_text(6, “err”) after if start_index then, I found that the problem was here: the program found the data, but could not find the packet header. After I tried to print the data directly to the gcs, I found 4 consecutive 255s in the data - it could see my packet header, but couldn’t find it?

After I tried adjusting the loop time and changing the packet header format, the program still stalled at this point.

After waiting for a long time, I also found that the data printed to the gcs all turned into 255. Does this mean that the buffer overflowed? How can I solve this problem?

Please help me, I really have no clue! Thank you for your help and have a nice day.

Okay, I debugged this program again. After deleting all the data judgments, I found that the script assigns nil to high_byte, which means that the data obtained by this program from the serial port may be fragmented. Is it because I cannot read the serial port at a speed of 100hz within the script?

I found that I made a lot of stupid mistakes, but now I have caught all these bugs–my flight controller has obtained the data I need!
Although no one provided me with help, I got help from the ardupilot community: I searched for many lua programs that can run normally in discuss, and corrected my mistakes!
Thank you all!

1 Like

Hello @Ben_bili

glad to read you found the errors, could you be so kind and upload the working script ?
Thanks

-- Define the serial port, find the first scripting mode serial port
local port = assert(serial:find_serial(0),"Could not find scripting serial port!")
port:begin(115200)
port:set_flow_control(0)

-- Define the packet header table
local header = {255, 255, 255, 255}
-- Define the number of motors
local num_motors = 8

-- Define the time when the last valid data was received
local last_valid_data_time = millis()
-- Define a function to find the packet header
function find_header(data, header)
    for i = 1, #data - #header + 1 do
        local found = true
        for j = 1, #header do
            if data[i + j - 1] ~= header[j] then
                found = false
                break
            end
        end
        if found then
            return i
        end
    end
    return nil
end
-- Define a function to extract data
function sub_array(data, start_index, end_index)
    local result = {}
    for i = start_index, end_index do
        result[#result + 1] = data[i]
    end
    return result
end

for i = 0, num_motors - 1 do
    esc_telem:set_rpm_scale(i, 1)
end

-- Define a function to read and parse serial data
function read_data()
    -- Check if there is at least 20 bytes of available data
if port:available() >=20 then
        -- Read all data from the serial port and tabulate it
        local data = {}
        local bytes =  port:available() 
    while bytes > 0 do
        data[#data+1]=port:read()
        bytes=bytes-1
    end

        -- Check if there is a packet header
        local start_index = find_header(data, header)  
        if start_index then      
            -- Check if there is enough data in the buffer
            if #data - start_index + 1 >= 20 then
                -- Extract the data packet
                data = sub_array(data, start_index, start_index + 20 - 1)
                -- Update the time when the last valid data was received
                last_valid_data_time = millis()
                -- Extract motor speed data
                local motor_speeds = {}
                for i = 1, num_motors do
                    local low_byte = data[5 + (i - 1) * 2]
                    local high_byte = data[6 + (i - 1) * 2]
                    motor_speeds[i] = low_byte + high_byte * 256
                end
                -- Update esc*_rpm values 
                for i = 1, num_motors do 
                    esc_telem:update_rpm(i - 1, motor_speeds[i], 0)
                  
                end 
            else do end -- Skip if there is not enough data 
            end 
        else do end -- Skip if no packet header is found 
        end 
end 

    -- Check if it has been more than one second since valid data was received 
    if millis() - last_valid_data_time > 1000 then 
        -- Send warning text to ground station 
        gcs:send_text(4, "no_rpm_data") 
        last_valid_data_time = millis() 
    end 

   return read_data,10 
end 

return read_data,10


Of course, what are you planning to do with it?
If you’re frustrated with Lua, maybe you can try letting AI help you, although AI is usually quite dumb, so you need some patience and basic knowledge.

Thanks a lot,
I have a system that sends telemetry data on serial that i would like to incorporate into the ardupilot stream. did some compiling from the templates, but failed on parameters locking.

Well, I think if you make some minor modifications to my code, such as the API and header, it should work. Good luck!

1 Like

That will be great, thanks alot :slight_smile:

hi ben thanks very much for sharing , can i ask you how did you make the rpm collector and is it gpio based? if so do you mind to share to me the details and perhaps the code? because i am trying to do the same like you but have no luck making it work