Display data send by companion computer in Mission Planner quick tab

Exactly. First you need to send some data…

1 Like

Update:
I could display the name of my variable but the value is 0,00… The Mavlink Inspector shows the true value (wich is 123,45)… Should I configure something else in MP?

@Eosbandi any idea how to fix this? The goal is very close :sweat_smile:

It is working at me. I send it from a lua script…
image
image

Your message is likely malformed. It could be your use of the colloquial comma rather than decimal point. Or it could be that you are sending the value in the wrong part of the data frame.

1 Like

@Eosbandi could you provide me your code please?
@Yuri_Rage
Maybe it’s helpful to show you my code, if I change the value from 129.8 to 129,8 I get an error message:

#include "mavlink.h"

const uint8_t pixhawk_sysid = 2;
const uint8_t pixhawk_compid = 2;

void setup() {
  Serial.begin(115200);
}

void loop() {
  sendNamedValueFloat();
  //delay(1000);
}

void sendNamedValueFloat() {
  mavlink_message_t msg;

  uint32_t time_boot_ms = millis();
  const char* name = "TEST_VAL";  // Variablen Name
  float value = 120;          // Wert

  // Nachricht Packen
  mavlink_msg_named_value_float_pack(pixhawk_sysid, pixhawk_compid, &msg, time_boot_ms, name, value);

  // Nachricht schicken
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
  Serial.write(buf, len);

}

Now I see what’s wrong. you sending a message with sysid 2 and component Id 2. Mission Planner handles different components separately. Use your drop-down below the connect button and select your component to display data from it. Note: this will display ONLY data from the selected component.
If you want to display the data alongside with the flight controller you have to send messages with the same sysid and component id as the flight controller.
This is not the best solution because it will generate some false packet errors on non sequential packet sequence numbers, but at least it will work.
For the best solution communicate onboard with a LUA script and send data to the GCS from the script.

1 Like

Unfortunately my drop down menu doesn’t show me different components (see attached image).
dd

I changed the sysis and compid to 1 (same as the FC) but that didn’t help since there was no data on the quick tab also the variable can’t be choosen.
This is very confusing…

But you think with the LUA script it will be possible to display both, the FC and the companion computer on quick tab?

For my it is not clear why I can see the name of the value (MAV_…) but it is not possible to display the float value itself…

Somehow this is not possible… I can just select “COM7-1-FIXED WING”

Even if I use the same comp and sys ID, I can’t see any incoming data

Since I’m not that experienced, could you please explain it more to me?

If you send the message from another sysid then you should send heartbeat messages as well.
There are one semi solution : You can send your messages with sysid=flight controller sysid and with component id = 0 (ALL) this will show up in the drop down

> If you want to display the data alongside with the flight controller you have to send messages with the same sysid and component id as the flight controller.
Sorry I was wrong with this one, the FC will not forward messages it got with it’s own sysid and compid.

Regarding LUA, YURI have an excellent tutorial in this topic.

1 Like

@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

@Yuri_Rage Thanks a lot for your help!! That’s highly appreciated!!
And yes of course I will work more to improve my CS knowledge, that is also a helpful advice!

@Eosbandi Also big thanks to you and your efforts!!

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!