Display data send by companion computer in Mission Planner quick tab

To close this issue, I added a PR to Mission Planner, which allows the propagation of incoming NAMED_FLOAT messages across components.

This means that from an external source, you can send NAMED_FLOAT messages with the same sysid as the flight controller but with a separate component id (not one or zero). These messages will be processed and added to the status variables of the flight controller component.
To be compliant with the mavlink protocol, your component also has to send heartbeat messages to get recognized. (The propagation will work without it).
If you need the original behavior to separate named_float across components then add the

<propagateNamedFloats>false</propagateNamedFloats>

Line to the config.xml

This PR will be available in the next beta update within a few days.

1 Like

I have modified the code so that I can receive 2 different temperature values in MP. It works perfectly!
But I also want to receive a pwm value in MP but the problem is that the values donā€™t get updated any more. It would be very helpful if someone could help me to debug this issue.

here is the Arduino code:

// Combined Code
#include <math.h>

#define TX_RATE_HZ 10
const uint8_t HEADER_BYTE = 0xFF;

uint32_t last_update_ms = 0;
uint8_t led_state = 0;

float calculateTemperature(int RawADC);
int readPWMValue();

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

void loop() {
  uint32_t now = millis();
  if (now - last_update_ms > 1000 / TX_RATE_HZ) {
    int sensorValue1 = analogRead(A0);
    int sensorValue2 = analogRead(A1);

    float temperature1 = calculateTemperature(sensorValue1);
    float temperature2 = calculateTemperature(sensorValue2);

    uint8_t checksum1 = highByte((int)temperature1) ^ lowByte((int)temperature1);
    uint8_t checksum2 = highByte((int)temperature2) ^ lowByte((int)temperature2);

    int pwmValue = readPWMValue();

    Serial.write(HEADER_BYTE);
    Serial.write(highByte((int)temperature1));
    Serial.write(lowByte((int)temperature1));
    Serial.write(checksum1);

    Serial.write(HEADER_BYTE);
    Serial.write(highByte((int)temperature2));
    Serial.write(lowByte((int)temperature2));
    Serial.write(checksum2);

    Serial.write(HEADER_BYTE);
    Serial.write(highByte(pwmValue));
    Serial.write(lowByte(pwmValue));

    led_state ^= 1;
    digitalWrite(LED_BUILTIN, led_state);
    last_update_ms = now;
  }
}

float calculateTemperature(int RawADC) {
  float Temp;
  Temp = log((10240000.0 / RawADC) - 10000.0);
  Temp = 1 / (0.001129148 + (0.000234125 + (0.0000000876741 * Temp * Temp)) * Temp);
  Temp = Temp - 273.15;
  return Temp;
}

int readPWMValue() {
  const int pwmPin = 2;
  unsigned long pulseDuration = pulseIn(pwmPin, HIGH);
  int pwmValue = map(pulseDuration, 1000, 2000, 0, 100);
  return pwmValue;
}

Lua script:

-- Updated Lua Script for 2 Temp Sensors and PWM
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(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 >= 12 then
        local header1, high1, low1, checksum1, header2, high2, low2, checksum2, header3, highPWM, lowPWM, checksumPWM =
            bytes[1], bytes[2], bytes[3], bytes[4], bytes[5], bytes[6], bytes[7], bytes[8], bytes[9], bytes[10], bytes[11], bytes[12]

        local tempVal1 = (high1 << 8) | low1
        local tempVal2 = (high2 << 8) | low2
        local pwmValue = (highPWM << 8) | lowPWM

        local calculatedChecksum1 = (high1 ~ low1) & 0xFF
        local calculatedChecksum2 = (high2 ~ low2) & 0xFF
        local calculatedChecksumPWM = (highPWM ~ lowPWM) & 0xFF

        if header1 == 0xFF and checksum1 == calculatedChecksum1 and
           header2 == 0xFF and checksum2 == calculatedChecksum2 and
           header3 == 0xFF and checksumPWM == calculatedChecksumPWM
        then
            gcs:send_named_float('TempVal1', tempVal1)
            gcs:send_named_float('TempVal2', tempVal2)
            gcs:send_named_float('PWMValue', pwmValue)
        else
            bad_frames = bad_frames + 1
            gcs:send_named_float('BAD_FR', bad_frames)
        end
    end

    return update, RUN_INTERVAL_MS
end

return update()

You donā€™t send the PWMChecksum from Arduino :slight_smile:

1 Like

Thanks again @Eosbandi, now it works fine! :sunglasses:

The new beta with this PR #3226 is not available yet, isnā€™t it?

It is thereā€¦ Added to the beta on Nov 8.

1 Like

Very nice, I just installed it is working great!