QGC Integration of winch data

Hi @RURAS,

QGC is open source, so it’s definitely possible, but because of how the MAVLink protocol and the QGC codebase are structured it can be somewhat complicated to add things to the interface, and doing so requires building your own custom version of QGC.

A couple of years ago I did a write up about adding a sensor to a MAVLink stream. Most likely the simplest approach is something similar to that, using NAMED_VALUE_FLOAT messages. I’ve just tested and it worked for me to make these modifications to the latest stable version of QGC (Stable_V4.2 branch), which could then receive MAVLink messages from a program sending the relevant message, like this Pymavlink script:

import time
from pymavlink import mavutil

def wait_conn(device):
    """ Sends a ping to develop UDP communication and waits for a response. """
    while not (msg := device.recv_match()):
        device.mav.ping_send(
            int((time.time() - BOOT_TIME) * 1e6), # Unix time since boot (microseconds)
            0, # Ping number
            0, # Request ping of all systems
            0  # Request ping of all components
        )
        time.sleep(0.5)


class Winch:
    def __init__(self):
        ... # TODO: implement connection details
        # this is the name QGC is searching for, and MUST be 9 characters or shorter
        self.message_name = b'WinchTrns'
    
    def get_value(self):
        """ Returns the next value from the winch. """
        # TODO: implement actual data fetching
        # pretend to be a slow sensor, with some random output values
        from random import randint
        time.sleep(0.5)
        return randint(-50, 50)


if __name__ == '__main__':
    BOOT_TIME = time.time()
    # establish connection to top-side computer
    direction = 'udpout'
    device_ip = 'localhost'
    port      = 14550
    print(f'connecting to {device_ip} via {direction} on {port=}.')
    qgc = mavutil.mavlink_connection(f'{direction}:{device_ip}:{port}', source_system=1)
    
    print('waiting for confirmation... ', end='')
    wait_conn(qgc)
    print('connection success!')
    
    # TODO: connect to winch
    winch = Winch()
    
    while 'reading data':
        qgc.mav.named_value_float_send(
            int((time.time() - BOOT_TIME) * 1e3),
            winch.message_name,
            winch.get_value()
        )

From there you can modify the telemetry display (hover over it then click the edit pencil at the top left corner), and add it:



As something of a side note, it seems the `Stable_V4.2` branch has a couple of warnings when trying to build, which I ignored to enable the build to complete (click to see details, if relevant)

by adding

QMAKE_CXXFLAGS_WARN_ON+=-Wno-unused-but-set-variable QMAKE_CXXFLAGS_WARN_ON+=-Wno-deprecated-declarations

as additional build arguments:

Ordinarily warnings shouldn’t be ignored, but given the code causing the warnings was from a supposedly stable version I decided to leave it alone, since it’s unlikely to cause issues.

1 Like