Reading current gain percentage and flight mode

Hi @Efe,

Yes, both of those are possible, although how to do so is currently not well documented. ArduSub sends the joystick gain via NAMED_VALUE_FLOAT messages with the name PilotGain, and the flight mode is sent as the custom_mode property of every HEARTBEAT message :slight_smile:

You can access them via something like this:

from pymavlink import mavutil, mavlink

... # connect to vehicle

def handle_named_value_float(msg):
    if msg.name == 'PilotGain':
        print(f'Gain is {msg.value:.2%}')

def handle_heartbeat(msg):
    flight_mode = mavlink.enums['SUB_MODE'][msg.custom_mode].name
    print(f'{flight_mode = }')

message_handlers = {
    'NAMED_VALUE_FLOAT': handle_named_value_float,
    'HEARTBEAT': handle_heartbeat,
}

... # loop and handle messages

and then use one of the approaches covered here to do the handling.

Note that depending on your onboard computer software and the other MAVLink connections involved the NAMED_VALUE_FLOAT messages may not be sent by default (normally QGC requests them), and there may be HEARTBEAT messages arriving from multiple different source ids and component ids (which may need to be filtered through by confirming that e.g. msg.get_srcComponent() == master.target_component).