Display data send by companion computer in Mission Planner quick tab

@starter-one, I edited this post with what I hope is helpful to you and will serve as an example to others.

The Arduino sketch writes a random value in 12-bit precision along with a 0xFF header byte and rudimentary single byte checksum.

The Lua script consumes that data, checking for validity, and passes it on to the GCS as named float values.

Follow the wiki instructions to enable Lua scripting and upload the script to your autopilot as a .lua file.

For the UART in use, set:
SERIALx_PROTOCOL,28
SERIALx_BAUD,115

Arduino C++ sketch:

#define TX_RATE_HZ 10
const uint8_t HEADER_BYTE = 0xFF;

uint32_t last_update_ms = 0;
uint8_t led_state = 0;

void setup() {
  Serial.begin(115200);
  pinMode(LED_BUILTIN, OUTPUT);
}

void loop() {
  uint32_t now = millis();
  if (now - last_update_ms > 1000 / TX_RATE_HZ) {
    uint16_t sensorValue = random(0, 4096);
    uint8_t checksum = highByte(sensorValue) ^ lowByte(sensorValue);
    Serial.write(HEADER_BYTE);
    Serial.write(highByte(sensorValue));
    Serial.write(lowByte(sensorValue));
    Serial.write(checksum);
    led_state ^= 1;
    digitalWrite(LED_BUILTIN, led_state);
    last_update_ms = now;
  }
}

Ardupilot Lua script:

local RUN_INTERVAL_MS = 50  -- 50ms == 20 Hz
local MAX_BUFFER = 128 -- prevent Lua timeout

local port = serial:find_serial(0)
local bad_frames = 0

port:begin(uint32_t(115200))
port:set_flow_control(0)

function update()
    local bytes = {}
    while port:available() > 0 do
        bytes[#bytes+1] = port:read()
        if #bytes > MAX_BUFFER then
            return update, RUN_INTERVAL_MS
        end
    end

    if #bytes ~= 4 then
        return update, RUN_INTERVAL_MS
    end

    if bytes[1] ~= 0xFF or bytes[4] ~= bytes[2] ~ bytes[3] then
        bad_frames = bad_frames + 1
        gcs:send_named_float('BAD_FR', bad_frames)
        return update, RUN_INTERVAL_MS
    end

    gcs:send_named_float('VAL', bytes[2] << 8 | bytes[3])
    gcs:send_named_float('BAD_FR', bad_frames)

    return update, RUN_INTERVAL_MS
end

return update()
3 Likes