Skip to content

Commit 03adf5e

Browse files
Ryanf55tpwrules
authored andcommitted
AP_Scripting: Add trisonica LI550 3D wind sensor logger
Signed-off-by: Ryan Friedman <[email protected]>
1 parent 91769c2 commit 03adf5e

File tree

2 files changed

+254
-0
lines changed

2 files changed

+254
-0
lines changed
Lines changed: 127 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
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, excluding 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 trisonica scripting port")
26+
return
27+
end
28+
29+
-- begin the serial port
30+
port:begin(230400)
31+
port:set_flow_control(0)
32+
33+
local function parse_wind_data(buf)
34+
-- Split the string up into key and values splitting on the default space delimiter.
35+
36+
local parsed_values = {}
37+
38+
-- Match any key-value pair where key is a string and value is a number
39+
for key, value in buf:gmatch("(%a+)%s*([%-%.%d]+)") do
40+
parsed_values[key] = tonumber(value) -- Store key-value pair in the table
41+
end
42+
43+
return parsed_values
44+
end
45+
46+
local tag_ids = nil
47+
local tag_id_str = ""
48+
local value_format = ""
49+
local last_keys = nil
50+
51+
local function log_wind_data(parsed)
52+
-- Given a table of parsed data, log it.
53+
54+
-- Collect keys from parsed and store as a list
55+
local current_keys = {}
56+
for k in pairs(parsed) do
57+
table.insert(current_keys, k)
58+
end
59+
table.sort(current_keys)
60+
61+
-- First packet, we must set last_keys.
62+
if not last_keys then
63+
last_keys = current_keys
64+
return
65+
end
66+
67+
-- Bail early if the first packet parsed only contained some of the keys.
68+
-- After the 2nd packet, it will stabilize.
69+
if #current_keys ~= #last_keys then
70+
last_keys = current_keys
71+
return
72+
end
73+
74+
for i = 1, #current_keys do
75+
if current_keys[i] ~= last_keys[i] then
76+
last_keys = current_keys
77+
return
78+
end
79+
end
80+
81+
-- Keys are now stable, so store them as tag_ids
82+
if not tag_ids then
83+
tag_ids = current_keys
84+
tag_id_str = table.concat(tag_ids, ',')
85+
value_format = string.rep('f', #tag_ids)
86+
gcs:send_text(MAV_SEVERITY.INFO, "Using tag_ids: " .. tag_id_str)
87+
end
88+
89+
90+
-- Build ordered values from tag_ids
91+
local values = {}
92+
for _, tag_id in ipairs(tag_ids) do
93+
table.insert(values, parsed[tag_id] or 0)
94+
end
95+
96+
assert(#tag_ids < 15, "#tag_ids=" .. #tag_ids)
97+
logger:write('W3D', tag_id_str, value_format, table.unpack(values))
98+
end
99+
100+
local buffer = ""
101+
-- the main update function that is used to read in data from serial port
102+
local function update()
103+
104+
105+
local n_bytes = port:available()
106+
while n_bytes > 0 do
107+
local byte = port:read()
108+
109+
if byte > -1 then
110+
local c = string.char(byte)
111+
buffer = buffer .. c
112+
113+
--ignore the \n because \r is sufficient to end parsing.
114+
if c == "\r" then
115+
local result = parse_wind_data(buffer)
116+
log_wind_data(result)
117+
buffer = ""
118+
end
119+
end
120+
n_bytes = n_bytes - 1
121+
end
122+
return update, 100
123+
end
124+
125+
gcs:send_text(MAV_SEVERITY.INFO, "trisonica-mini.lua running...")
126+
127+
return update, 100
Lines changed: 127 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
1+
# Trisonica LI-550 Mini Wind Sensor Logger
2+
3+
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.
4+
5+
For sensor details, visit:
6+
🔗 https://www.licor.com/products/trisonica/LI-550-mini
7+
8+
## Features
9+
10+
- Parses and logs ASCII data strings from the Trisonica LI-550 Mini in BIN logs
11+
- Logs fields using a dynamically generated tag list from the **first packet**
12+
- Ignores extraneous fields in subsequent messages not present in the first
13+
- Compatible with **ArduPilot scripting serial port** interface
14+
- Supports high-speed 230400 baud data stream
15+
- Uses BIN log name `W3D` for all data
16+
17+
## Parameters
18+
19+
Set the following parameters:
20+
21+
| Parameter | Value | Description |
22+
|----------------|----------|--------------------------------|
23+
| `SCR_ENABLE` | `1` | Enable Lua scripting |
24+
| `SERIALx_PROTOCOL` | `28` | Scripting protocol for SERIALx |
25+
26+
27+
> Replace `SERIALx` with the appropriate serial port used on your hardware.
28+
29+
## Sensor configuration
30+
31+
Use Trisonica's [CLI](logger:write) to configure the unit. On Linux, you can use `screen` to interract with the device:
32+
```bash
33+
screen /dev/ttyUSB0 230400
34+
```
35+
You should see data displayed. Enter configuration mode with `Ctrl+C`.
36+
You should now see data streaming stop and a terminal prompt `>`.
37+
38+
Set the Trisonica sensor baudrate to **230400** in its configuration software using the `baudrate` command like so:
39+
```bash
40+
baudrate 230400
41+
```
42+
43+
You must also **enable all fields you want to log**. A recommended set is as follows. See the `Enabled` column.
44+
45+
```bash
46+
display
47+
```
48+
49+
```
50+
-----------------------------------------------------------------------------------------
51+
| Name | Description | Tagged | Tag | Decimals | Enabled | Units |
52+
-----------------------------------------------------------------------------------------
53+
| IDTag | ID Tag | Yes | | | | |
54+
| S | Wind Speed 3D | Yes | S | 2 | | m/s |
55+
| S2D | Wind Speed 2D | Yes | S2 | 2 | | m/s |
56+
| D | Horiz Wind Direction | Yes | D | 0 | | Degrees |
57+
| DV | Vert Wind Direction | Yes | DV | 0 | | Degrees |
58+
| U | U Vector | Yes | U | 2 | Yes | m/s |
59+
| V | V Vector | Yes | V | 2 | Yes | m/s |
60+
| W | W Vector | Yes | W | 2 | Yes | m/s |
61+
| T | Temperature | Yes | T | 2 | Yes | C |
62+
| Cs | Speed of Sound | Yes | C | 2 | | m/s |
63+
| RHTemp | RH Temp Sensor | Yes | RHST | 2 | | C |
64+
| RH | RH Humidity Sensor | Yes | RHSH | 2 | | % |
65+
| H | Humidity | Yes | H | 2 | Yes | % |
66+
| DP | DewPoint | Yes | DP | 2 | | C |
67+
| PTemp | Pressure Temp Sensor | Yes | PST | 2 | | C |
68+
| P | Pressure Sensor | Yes | P | | Yes | hPa |
69+
| Density | Air Density | Yes | AD | | Yes | kg/m^3 |
70+
| LevelX | Level X | Yes | AX | | Yes | |
71+
| LevelY | Level Y | Yes | AY | | Yes | |
72+
| LevelZ | Level Z | Yes | AZ | | Yes | |
73+
| Pitch | Pitch | Yes | PI | 1 | Yes | Degrees |
74+
| Roll | Roll | Yes | RO | 1 | Yes | Degrees |
75+
| CTemp | Compass Temp | Yes | MT | 1 | | C |
76+
| MagX | Compass X | Yes | MX | | | |
77+
| MagY | Compass Y | Yes | MY | | | |
78+
| MagZ | Compass Z | Yes | MZ | | | |
79+
| Heading | Compass Heading | Yes | MD | 0 | Yes | Degrees |
80+
| TrueHead | True Heading | Yes | TD | 0 | Yes | Degrees |
81+
-----------------------------------------------------------------------------------------
82+
```
83+
84+
You can enable tags like so:
85+
```bash
86+
show T
87+
```
88+
89+
Or disable them from the data stream like so:
90+
```bash
91+
hide T
92+
```
93+
94+
You must not enable more than 12 outputs due to limitations in this script and ArduPilot's dataflash logger.
95+
96+
Finally, increase the output rate to the maximum of **10 Hz**.
97+
```bash
98+
outputrate 10
99+
```
100+
101+
Once configuration is complete, exit screen with
102+
```bash
103+
ctr+A k y
104+
```
105+
106+
If you take longer than a minute to configure, the unit will re-enter streaming mode.
107+
108+
## SITL Testing
109+
110+
You can connect a real serial device to SITL using a passthrough UART setup.
111+
For example, using SERIAL5 connected to ttyUSB0.
112+
113+
```bash
114+
./Tools/autotest/sim_vehicle.py -v Plane --console --map -A "--serial5=uart:/dev/ttyUSB0" -D
115+
```
116+
117+
Then view the `W3D` entries in your favorite dataflash (BIN) log analyzer.
118+
For MAVExplorer, try graphing wind speeds against airspeed.
119+
120+
```bash
121+
graph W3D.U W3D.W W3D.V ARSP.Airspeed
122+
```
123+
124+
## Future Improvements
125+
126+
* Use the wind data as input to the EKF for wind speed
127+
* Use the Trisonica API to have ArduPilot configure the correct data outputs and rates

0 commit comments

Comments
 (0)