|
| 1 | +--[[ |
| 2 | + adsb_send.lua: send a simulated ADSB vehicle flying a 500m radius circle |
| 3 | +
|
| 4 | + This script demonstrates how to send ADSB_VEHICLE MAVLink messages using |
| 5 | + -- mavlink:send_chan() with manual struct packing (no MAVLink module required) |
| 6 | +--]] |
| 7 | + |
| 8 | +-- initialise mavlink (no rx needed, only tx) |
| 9 | +mavlink:init(1, 0) |
| 10 | + |
| 11 | +local ADSB_VEHICLE_MSGID = 246 |
| 12 | + |
| 13 | +-- ADSB flags bitmask values |
| 14 | +local ADSB_FLAGS_VALID_COORDS = 1 |
| 15 | +local ADSB_FLAGS_VALID_ALTITUDE = 2 |
| 16 | +local ADSB_FLAGS_VALID_HEADING = 4 |
| 17 | +local ADSB_FLAGS_VALID_VELOCITY = 8 |
| 18 | +local ADSB_FLAGS_VALID_CALLSIGN = 16 |
| 19 | +local ADSB_FLAGS_SIMULATED = 64 |
| 20 | +local ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 |
| 21 | + |
| 22 | +-- |
| 23 | +-- Send an ADSB_VEHICLE message on all MAVLink channels |
| 24 | +-- |
| 25 | +-- lat_deg : latitude in degrees |
| 26 | +-- lng_deg : longitude in degrees |
| 27 | +-- alt_amsl_m : altitude AMSL in metres |
| 28 | +-- heading_deg : course over ground in degrees (0=north, clockwise) |
| 29 | +-- speed_mps : horizontal speed in m/s |
| 30 | +-- vspeed_mps : vertical speed in m/s (positive = up) |
| 31 | +-- icao_address : 24-bit ICAO address |
| 32 | +-- callsign : up to 8 character string |
| 33 | +-- squawk : squawk code in decimal (e.g. 1200 for VFR) |
| 34 | +-- emitter_type : ADSB_EMITTER_TYPE enum value |
| 35 | +-- flags : ADSB_FLAGS bitmask |
| 36 | +-- |
| 37 | +local function send_ADSB_VEHICLE(lat_deg, lng_deg, alt_amsl_m, heading_deg, |
| 38 | + speed_mps, vspeed_mps, icao_address, |
| 39 | + callsign, squawk, emitter_type, flags) |
| 40 | + -- pad or truncate callsign to exactly 9 bytes (8 chars + null) |
| 41 | + local cs = callsign .. string.rep("\0", 9) |
| 42 | + cs = string.sub(cs, 1, 9) |
| 43 | + |
| 44 | + -- MAVLink wire order: fields sorted by type size descending, then XML order |
| 45 | + -- uint32: ICAO_address, lat, lon, altitude (4 x I4/i4) |
| 46 | + -- uint16: heading, hor_velocity, ver_velocity, (5 x I2/i2) |
| 47 | + -- flags, squawk |
| 48 | + -- uint8: altitude_type (1 x B) |
| 49 | + -- char[9]: callsign (c9) |
| 50 | + -- uint8: emitter_type, tslc (2 x B) |
| 51 | + local payload = string.pack("<I4i4i4i4 I2I2i2I2I2 Bc9BB", |
| 52 | + icao_address, |
| 53 | + math.floor(lat_deg * 1e7), -- degE7 |
| 54 | + math.floor(lng_deg * 1e7), -- degE7 |
| 55 | + math.floor(alt_amsl_m * 1000), -- mm |
| 56 | + math.floor(heading_deg * 100), -- cdeg |
| 57 | + math.floor(speed_mps * 100), -- cm/s |
| 58 | + math.floor(vspeed_mps * 100), -- cm/s |
| 59 | + flags, |
| 60 | + squawk, |
| 61 | + 0, -- altitude_type: PRESSURE_QNH |
| 62 | + cs, |
| 63 | + emitter_type, |
| 64 | + 0) -- tslc |
| 65 | + |
| 66 | + for chan = 0, 5 do |
| 67 | + mavlink:send_chan(chan, ADSB_VEHICLE_MSGID, payload) |
| 68 | + end |
| 69 | +end |
| 70 | + |
| 71 | +-- circle parameters |
| 72 | +local RADIUS_M = 500 -- circle radius in metres |
| 73 | +local ALT_AMSL_M = 100 -- altitude AMSL in metres |
| 74 | +local SPEED_MPS = 50 -- ground speed in m/s |
| 75 | +local ICAO_ADDR = 0xFABCDE -- fake ICAO address (0xF00000-0xFFFFFF is unallocated) |
| 76 | +local CALLSIGN = "SIM12345" |
| 77 | +local UPDATE_HZ = 5 -- send rate |
| 78 | + |
| 79 | +local FLAGS = ADSB_FLAGS_VALID_COORDS + ADSB_FLAGS_VALID_ALTITUDE |
| 80 | + + ADSB_FLAGS_VALID_HEADING + ADSB_FLAGS_VALID_VELOCITY |
| 81 | + + ADSB_FLAGS_VALID_CALLSIGN + ADSB_FLAGS_SIMULATED |
| 82 | + + ADSB_FLAGS_VERTICAL_VELOCITY_VALID |
| 83 | + |
| 84 | +-- angular rate in rad/s |
| 85 | +local OMEGA = SPEED_MPS / RADIUS_M |
| 86 | +local angle_rad = 0 |
| 87 | + |
| 88 | +local function update() |
| 89 | + local home = ahrs:get_home() |
| 90 | + if not home then |
| 91 | + return update, 1000 |
| 92 | + end |
| 93 | + |
| 94 | + local center_lat = home:lat() |
| 95 | + local center_lng = home:lng() |
| 96 | + local alt_m = ALT_AMSL_M + home:alt()*0.01 |
| 97 | + |
| 98 | + local dt = 1.0 / UPDATE_HZ |
| 99 | + angle_rad = angle_rad + OMEGA * dt |
| 100 | + if angle_rad > 2 * math.pi then |
| 101 | + angle_rad = angle_rad - 2 * math.pi |
| 102 | + end |
| 103 | + |
| 104 | + -- compute position on circle |
| 105 | + local pos = Location() |
| 106 | + pos:lat(center_lat) |
| 107 | + pos:lng(center_lng) |
| 108 | + pos:alt(math.floor(alt_m * 100)) |
| 109 | + pos:offset_bearing(math.deg(angle_rad), RADIUS_M) |
| 110 | + |
| 111 | + -- heading is tangent to circle (90 degrees ahead of radial) |
| 112 | + local heading_deg = math.deg(angle_rad) + 90 |
| 113 | + if heading_deg >= 360 then |
| 114 | + heading_deg = heading_deg - 360 |
| 115 | + end |
| 116 | + |
| 117 | + send_ADSB_VEHICLE( |
| 118 | + pos:lat() / 1e7, -- back to degrees |
| 119 | + pos:lng() / 1e7, -- back to degrees |
| 120 | + alt_m, |
| 121 | + heading_deg, |
| 122 | + SPEED_MPS, |
| 123 | + 0, -- no vertical speed |
| 124 | + ICAO_ADDR, |
| 125 | + CALLSIGN, |
| 126 | + 1200, -- VFR squawk |
| 127 | + 1, -- ADSB_EMITTER_TYPE_LIGHT |
| 128 | + FLAGS |
| 129 | + ) |
| 130 | + |
| 131 | + return update, math.floor(1000 / UPDATE_HZ) |
| 132 | +end |
| 133 | + |
| 134 | +return update() |
0 commit comments