Skip to content

AP_Scripting: Add wind decoder for Trisonica LI-550 #30054

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
May 25, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
127 changes: 127 additions & 0 deletions libraries/AP_Scripting/examples/trisonica-mini.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
-- Script decodes and logs wind sensor data for Trisonica LI-550 mini
-- https://www.licor.com/products/trisonica/LI-550-mini

-- Parameters:
-- SCR_ENABLE 1
-- SERIAL5_PROTOCOL 28

-- In SITL, you can enable serial ports to connect to the real device.
-- https://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html#the-8-uarts
-- ./Tools/autotest/sim_vehicle.py -v Plane --console --map -A "--serial5=uart:/dev/ttyUSB0" -D

-- Remember to change baud to 230k in the sensor setup and enable the fields you want.
-- Also, enable 10Hz output instead of the default 5Hz.

-- Example data string (excluding quotes, excluding the carriage return line feed ending)
-- "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"

-- Log severities
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

-- find the serial first (0) scripting serial port instance
local port = serial:find_serial(0)

if not port then
gcs:send_text(MAV_SEVERITY.EMERGENCY, "no trisonica scripting port")
return
end

-- begin the serial port
port:begin(230400)
port:set_flow_control(0)

local function parse_wind_data(buf)
-- Split the string up into key and values splitting on the default space delimiter.

local parsed_values = {}

-- Match any key-value pair where key is a string and value is a number
for key, value in buf:gmatch("(%a+)%s*([%-%.%d]+)") do
parsed_values[key] = tonumber(value) -- Store key-value pair in the table
end

return parsed_values
end

local tag_ids = nil
local tag_id_str = ""
local value_format = ""
local last_keys = nil

local function log_wind_data(parsed)
-- Given a table of parsed data, log it.

-- Collect keys from parsed and store as a list
local current_keys = {}
for k in pairs(parsed) do
table.insert(current_keys, k)
end
table.sort(current_keys)

-- First packet, we must set last_keys.
if not last_keys then
last_keys = current_keys
return
end

-- Bail early if the first packet parsed only contained some of the keys.
-- After the 2nd packet, it will stabilize.
if #current_keys ~= #last_keys then
last_keys = current_keys
return
end

for i = 1, #current_keys do
if current_keys[i] ~= last_keys[i] then
last_keys = current_keys
return
end
end

-- Keys are now stable, so store them as tag_ids
if not tag_ids then
tag_ids = current_keys
tag_id_str = table.concat(tag_ids, ',')
value_format = string.rep('f', #tag_ids)
gcs:send_text(MAV_SEVERITY.INFO, "Using tag_ids: " .. tag_id_str)
end


-- Build ordered values from tag_ids
local values = {}
for _, tag_id in ipairs(tag_ids) do
table.insert(values, parsed[tag_id] or 0)
end

assert(#tag_ids < 15, "#tag_ids=" .. #tag_ids)
logger:write('W3D', tag_id_str, value_format, table.unpack(values))
end

local buffer = ""
-- the main update function that is used to read in data from serial port
local function update()


local n_bytes = port:available()
while n_bytes > 0 do
local byte = port:read()

if byte > -1 then
local c = string.char(byte)
buffer = buffer .. c

--ignore the \n because \r is sufficient to end parsing.
if c == "\r" then
local result = parse_wind_data(buffer)
log_wind_data(result)
buffer = ""
end
end
n_bytes = n_bytes - 1
end
return update, 100
end

gcs:send_text(MAV_SEVERITY.INFO, "trisonica-mini.lua running...")

return update, 100
127 changes: 127 additions & 0 deletions libraries/AP_Scripting/examples/trisonicia-mini.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
# Trisonica LI-550 Mini Wind Sensor Logger

This Lua script reads and logs wind sensor data from the **Trisonica LI-550 Mini** ultrasonic wind sensor connected via serial. It decodes ASCII-formatted key-value pairs and logs the data using dynamic field tags on the `W3D` logging stream.

For sensor details, visit:
🔗 https://www.licor.com/products/trisonica/LI-550-mini

## Features

- Parses and logs ASCII data strings from the Trisonica LI-550 Mini in BIN logs
- Logs fields using a dynamically generated tag list from the **first packet**
- Ignores extraneous fields in subsequent messages not present in the first
- Compatible with **ArduPilot scripting serial port** interface
- Supports high-speed 230400 baud data stream
- Uses BIN log name `W3D` for all data

## Parameters

Set the following parameters:

| Parameter | Value | Description |
|----------------|----------|--------------------------------|
| `SCR_ENABLE` | `1` | Enable Lua scripting |
| `SERIALx_PROTOCOL` | `28` | Scripting protocol for SERIALx |


> Replace `SERIALx` with the appropriate serial port used on your hardware.

## Sensor configuration

Use Trisonica's [CLI](logger:write) to configure the unit. On Linux, you can use `screen` to interract with the device:
```bash
screen /dev/ttyUSB0 230400
```
You should see data displayed. Enter configuration mode with `Ctrl+C`.
You should now see data streaming stop and a terminal prompt `>`.

Set the Trisonica sensor baudrate to **230400** in its configuration software using the `baudrate` command like so:
```bash
baudrate 230400
```

You must also **enable all fields you want to log**. A recommended set is as follows. See the `Enabled` column.

```bash
display
```

```
-----------------------------------------------------------------------------------------
| Name | Description | Tagged | Tag | Decimals | Enabled | Units |
-----------------------------------------------------------------------------------------
| IDTag | ID Tag | Yes | | | | |
| S | Wind Speed 3D | Yes | S | 2 | | m/s |
| S2D | Wind Speed 2D | Yes | S2 | 2 | | m/s |
| D | Horiz Wind Direction | Yes | D | 0 | | Degrees |
| DV | Vert Wind Direction | Yes | DV | 0 | | Degrees |
| U | U Vector | Yes | U | 2 | Yes | m/s |
| V | V Vector | Yes | V | 2 | Yes | m/s |
| W | W Vector | Yes | W | 2 | Yes | m/s |
| T | Temperature | Yes | T | 2 | Yes | C |
| Cs | Speed of Sound | Yes | C | 2 | | m/s |
| RHTemp | RH Temp Sensor | Yes | RHST | 2 | | C |
| RH | RH Humidity Sensor | Yes | RHSH | 2 | | % |
| H | Humidity | Yes | H | 2 | Yes | % |
| DP | DewPoint | Yes | DP | 2 | | C |
| PTemp | Pressure Temp Sensor | Yes | PST | 2 | | C |
| P | Pressure Sensor | Yes | P | | Yes | hPa |
| Density | Air Density | Yes | AD | | Yes | kg/m^3 |
| LevelX | Level X | Yes | AX | | Yes | |
| LevelY | Level Y | Yes | AY | | Yes | |
| LevelZ | Level Z | Yes | AZ | | Yes | |
| Pitch | Pitch | Yes | PI | 1 | Yes | Degrees |
| Roll | Roll | Yes | RO | 1 | Yes | Degrees |
| CTemp | Compass Temp | Yes | MT | 1 | | C |
| MagX | Compass X | Yes | MX | | | |
| MagY | Compass Y | Yes | MY | | | |
| MagZ | Compass Z | Yes | MZ | | | |
| Heading | Compass Heading | Yes | MD | 0 | Yes | Degrees |
| TrueHead | True Heading | Yes | TD | 0 | Yes | Degrees |
-----------------------------------------------------------------------------------------
```

You can enable tags like so:
```bash
show T
```

Or disable them from the data stream like so:
```bash
hide T
```

You must not enable more than 12 outputs due to limitations in this script and ArduPilot's dataflash logger.

Finally, increase the output rate to the maximum of **10 Hz**.
```bash
outputrate 10
```

Once configuration is complete, exit screen with
```bash
ctr+A k y
```

If you take longer than a minute to configure, the unit will re-enter streaming mode.

## SITL Testing

You can connect a real serial device to SITL using a passthrough UART setup.
For example, using SERIAL5 connected to ttyUSB0.

```bash
./Tools/autotest/sim_vehicle.py -v Plane --console --map -A "--serial5=uart:/dev/ttyUSB0" -D
```

Then view the `W3D` entries in your favorite dataflash (BIN) log analyzer.
For MAVExplorer, try graphing wind speeds against airspeed.

```bash
graph W3D.U W3D.W W3D.V ARSP.Airspeed
```

## Future Improvements

* Use the wind data as input to the EKF for wind speed
* Use the Trisonica API to have ArduPilot configure the correct data outputs and rates
Loading