|
| 1 | +-- Script decodes and logs wind sensor data for Trisonica LI-550 mini |
| 2 | +-- https://www.licor.com/products/trisonica/LI-550-mini |
| 3 | + |
| 4 | +-- Parameters: |
| 5 | +-- SCR_ENABLE 1 |
| 6 | +-- SERIAL5_PROTOCOL 28 |
| 7 | + |
| 8 | +-- In SITL, you can enable serial ports to connect to the real device. |
| 9 | +-- https://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html#the-8-uarts |
| 10 | +-- ./Tools/autotest/sim_vehicle.py -v Plane --console --map -A "--serial5=uart:/dev/ttyUSB0" -D |
| 11 | + |
| 12 | +-- Remember to change baud to 230k in the sensor setup and enable the fields you want. |
| 13 | +-- Also, enable 10Hz output instead of the default 5Hz. |
| 14 | + |
| 15 | +-- Example data string (excluding quotes, including the carriage return line feed ending) |
| 16 | +-- "S 00.08 S2 00.07 D 245 DV 033 U 00.06 V 00.03 W 00.05 T 55889220.00 C 346.68 H 17.92 DP 03.68 P -099.70 AD 0.0000000 AX -2913 AY -3408 AZ -16600 PI 011.4 RO 009.8 MX -619 MY 845 MZ 782 MD 337 TD 337" |
| 17 | + |
| 18 | +-- Log severities |
| 19 | +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} |
| 20 | + |
| 21 | +-- find the serial first (0) scripting serial port instance |
| 22 | +local port = serial:find_serial(0) |
| 23 | + |
| 24 | +if not port then |
| 25 | + gcs:send_text(MAV_SEVERITY.EMERGENCY, "No Scripting Serial Port") |
| 26 | + return |
| 27 | +end |
| 28 | + |
| 29 | +-- begin the serial port |
| 30 | +port:begin(230400) |
| 31 | +port:set_flow_control(0) |
| 32 | + |
| 33 | +local buffer = "" |
| 34 | + |
| 35 | +local function parse_wind_data(buf) |
| 36 | + -- Split the string up into key and values splitting on the default space delimiter. |
| 37 | + |
| 38 | + local parsed_values = {} |
| 39 | + |
| 40 | + -- Match any key-value pair where key is a string and value is a number |
| 41 | + for key, value in buf:gmatch("(%a+)%s*([%-%.%d]+)") do |
| 42 | + parsed_values[key] = tonumber(value) -- Store key-value pair in the table |
| 43 | + end |
| 44 | + |
| 45 | + return parsed_values |
| 46 | +end |
| 47 | + |
| 48 | +local function log_wind_data(parsed) |
| 49 | + -- Given a table of parsed data, log it. |
| 50 | + |
| 51 | + local tag_ids = {} |
| 52 | + local values = {} |
| 53 | + -- Build up the logger list of dynamic tag ID's. |
| 54 | + for tag_id, v in pairs(parsed) do |
| 55 | + table.insert(tag_ids, tag_id) |
| 56 | + table.insert(values, v) |
| 57 | + end |
| 58 | + local tag_id_str = table.concat(tag_ids, ',') |
| 59 | + local value_format = string.rep('f', #tag_ids) |
| 60 | + |
| 61 | + assert(#tag_ids < 15, "#tag_ids=" .. #tag_ids) |
| 62 | + logger.write('W3D', tag_id_str, value_format, |
| 63 | + table.unpack(values)) |
| 64 | +end |
| 65 | + |
| 66 | + |
| 67 | +-- the main update function that is used to read in data from serial port |
| 68 | +local function update() |
| 69 | + |
| 70 | + if not port then |
| 71 | + gcs:send_text(0, "no Scripting Serial Port") |
| 72 | + return update, 100 |
| 73 | + end |
| 74 | + |
| 75 | + -- gcs:send_text(MAV_SEVERITY.INFO, "update()") |
| 76 | + |
| 77 | + local n_bytes = port:available() |
| 78 | + while n_bytes > 0 do |
| 79 | + local byte = port:read() |
| 80 | + |
| 81 | + if byte then |
| 82 | + local c = string.char(byte) |
| 83 | + buffer = buffer .. c |
| 84 | + |
| 85 | + if c == "\r" then |
| 86 | + local result = parse_wind_data(buffer) |
| 87 | + log_wind_data(result) |
| 88 | + buffer = "" |
| 89 | + end |
| 90 | + end |
| 91 | + n_bytes = n_bytes - 1 |
| 92 | + end |
| 93 | + return update, 100 |
| 94 | +end |
| 95 | + |
| 96 | +gcs:send_text(MAV_SEVERITY.INFO, "wind-decode.lua running...") |
| 97 | + |
| 98 | +return update, 100 |
| 99 | + |
| 100 | + |
0 commit comments