Check what mode vehicle is in using pymavlink

How do you check, or what command do you send via pymavlink/mavutils to check to see what the current Mode the vehicle is in? Below can change the modes but how do I know what mode state the vehicle is in currently?

import sys
from pymavlink import mavutil
# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
# Wait a heartbeat before sending commands
master.wait_heartbeat()
# Choose a mode
mode = 'STABILIZE'

# Get mode ID
mode_id = master.mode_mapping()[mode]
# Set new mode

master.mav.set_mode_send(
    master.target_system,
    mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
    mode_id)

You can check out HEARTBEAT messages to get the flight mode. But I believe you need to enable receiving messages first. Something like this:

# Insert this after connecting to autopilot, not sure if needed
master.mav.request_data_stream_send(master.target_system, master.target_component, mavutil.mavlink.MAV_DATA_STREAM_ALL, 1, 1)

# Get HEARTBEAT message
msg = master.recv_match(type = 'HEARTBEAT', blocking = False)
if msg:
    mode = mavutil.mode_string_v10(msg)

Also, I would do it in a separate infinte loop so you don’t miss any message.

I tried the above code. It does pull the mode and I receive “HOLD” as an output. However when I change the mode to guided and run the code again it still says “HOLD”. I am wondering if this mode message is referring to the initial mode at startup (which I have as HOLD).

Try to use a loop:

import sys
from pymavlink import mavutil
# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
# Wait a heartbeat before sending commands
master.wait_heartbeat()

while True:
    msg = master.recv_match(type = 'HEARTBEAT', blocking = False)
    if msg:
        mode = mavutil.mode_string_v10(msg)
        print(mode)
1 Like

Thanks! Got it to work! Looks like the first couple messages are from the previous mode but after that it updates to the current