Accessing real-time MAVLink messages via pymavlink

Greetings,
We are working on a AUV system. Currently i am searching that how can i access to the real-time MAVLink messages. ( I want to access the datas which can seen on QGround’s MAVLink Inspector section). I’m doing researches for a long while and had no results. We are using a Pixhawk2.4.8 and a Jetson Nano.

For instance,
i am using a depth sensor, how can i access to the current depth values in real time via pymavlink?
or
how can i access to the AHRS2 values that constantly updating on terminal?

I’ve succeeded to connect with my master computer and succeeded to print "PARAM_VALUES" on terminal, but when i try to change it to "AHRS2" from "PARAM_VALUES" it returns None on terminal.

Note: Terminal returns Null on "AHRS2" whether i arm the vehicle or not.

import time
import sys
from pymavlink import mavutil

master = mavutil.mavlink_connection("/dev/ttyACM0", baud=115200)
master.wait_heartbeat()
print("HEARTBEAT_DONE")
 
master.param_fetch_all()
 
while True:
            m = master.recv_match(type = "PARAM_VALUES", blocking = True, timeout = 1)
            print(m)
            if m is None:
                        break

Any help will be appreciated, thanks.

Hi @toosat, welcome to the forum :slight_smile:

The Pixhawk will send a small set of vital messages by default, but other messages you’re interested in need to be requested. QGC requests a large set of messages automatically, whereas if you’re connecting directly to the Pixhawk with Pymavlink you’ll need to request those messages yourself. You can request a message to be sent regularly using MAV_CMD_SET_MESSAGE_INTERVAL, which we have a Pymavlink example for here :slight_smile:

There’s an alternative implementation here, as part of a broader full program example of controlling a vehicle (requires Python >= 3.8). The code is a bit more involved, but as a result it should be easier/simpler to use.

1 Like

Thanks for the quick response @EliotBR ,
Yesterday, we implemented the code based on information that you gave me. And we succeded to see the variables that we wanted to see on terminal. I’ll be posting my code here in a few days to help other forum users.

2 Likes

As one can see in the image, I’m currently only getting a heartbeat and timesync data back from the Pixhawk 4. Any idea on how I can get more? Like Attitude or GPS data?

Thank you a lot for the help in advance :slight_smile:.

Best regards

Per

Hi @PerFrivik,

I’ve moved your comment into this post because it’s on the same topic. I’d recommend you read my comment above, and ask follow-ups if something isn’t clear :slight_smile:

1 Like

You’re the best of the best! Exactly what I needed, thank you so much again!

1 Like

Hi @PerFrivik ,
Here is my code to get ‘alt’ value through “VFR_HUD” message. I hope it’ll be helpful for you.

def request_message_interval(master, message_input: str, frequency_hz: float):

    message_name = "MAVLINK_MSG_ID_" + message_input

    message_id = getattr(mavutil.mavlink, message_name)

    master.mav.command_long_send(

        master.target_system, master.target_component,

        mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0,

        message_id,

        1e6 / frequency_hz,

        0,

        0, 0, 0, 0)

   

    print("Requested the message successfully.")

   

def get_requested_data(master, message_name: str, dict_key: str, value_unit: str, save_name: str):

    try:

        message_index = 0

        dict1 = master.recv_match(type= message_name, blocking=True, timeout=0.1).to_dict()

        dict_value = dict1[dict_key]

       

        toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit

        with open(save_name, 'a') as file:

            file.write(toWrite)

            file.write('\n')  

            message_index += 1

    except:

        pass

request_message_interval(master, "VFR_HUD", 1)

while True:

    try:

        get_requested_data(master, "VFR_HUD", 'alt', "m", save_name)

    except:

        pass

You can use these functions to get any message you want. You just need to rename the message names with the ones you want. Additionally these functions are saving the message outputs to a empty file.
Regards.

1 Like

Hello Toosat,

I really appriciate the help :), thank you so much!

1 Like

I use your and some other method but it seems like I’m only getting heartbeat and timesync messages. Do you know how can I fix this? I think it’s related to some connection issue but I’m not sure. I can run the same command in my laptop but not in laptop. Baud rates is correct.

Edit: I think it somehow related to my first connection. If I open my laptop/raspberry and directly try to print the mavlink messages I’m only getting the heartbeat. But first if I give some order via that mavlink (such as calling the parameters in mission planner, or arming the motors), I can receive the all mavlink messages.

Should I put some command before the getting the parameters??

Hi @emir0723, welcome to the forum :slight_smile:

To receive messages beyond the defaults you’ll need to either

  1. Request them individually, as in my first comment, or
  2. Set the relevant stream group rate (if the message(s) you’re interested in are in one of the available groups)

As mentioned in my first comment, Control Station Software (like QGroundControl and Mission Planner) will request particular message rates when they connect to the vehicle, so if you open one of those softwares before running your own program then there will be additional messages being streamed because they’ve been requested.

Parameters are not accessed via standard MAVLink streams - they use the Parameter Protocol, which we have a couple of basic pymavlink examples for here.

Hi, thanks for the information on how to do this. I tried out this code below but I did not get the output I want. So I want the realtime RC parameters like RC1, RC2…RC7 ( Futaba Controller). I am trying to control my gimbal, Gremsy T7 which I have can control. The gimbal is connected to the telem1 port of my OrangeCube+. The RC receiver is connected to the RCIN pin of the OrangeCube+. I am trying to get the data that goes to the Gremsy through TELEM2.

from pymavlink import mavutil

# Configure the serial port
serial_port = '/dev/ttyUSB0'  # Since we are using FTDI to serial port
baud_rate = 57600  # Set the baud rate according to your setup

# Start a connection listening the serial port
mavlink_connection = mavutil.mavlink_connection(serial_port, baud=baud_rate)

# Wait for the first heartbeat 
# This sets the system and component ID of remote system for the link and prints it 
mavlink_connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (mavlink_connection.target_system, mavlink_connection.target_component))


#function to request the PARAM stream

def request_message_interval(master, message_input: str, frequency_hz: float):

    message_name = "MAVLINK_MSG_ID_" + message_input

    message_id = getattr(mavutil.mavlink, message_name)

    master.mav.command_long_send(master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0, message_id, 1e6/ frequency_hz, 0, 0, 0, 0, 0)

    print("Requested the message successfully.")

   


request_message_interval(mavlink_connection, "RC_CHANNELS_RAW", 1.0)


#Doubt, how will the RC values mounted in the MNT2 of TELEM2 be availbale in TELEM1?
while True:
    # Read a MAVLink message from TELEM2
    message = mavlink_connection.recv_match(type= "RC_CHANNELS_RAW", blocking=True, timeout=0.1)
    #print("Message received sucessfully")
    print('Received',message)
    if message:
        print('Received',message)
        # Extract RC channel values from the message
        rc_channel_1 = message.chan1_raw
        rc_channel_2 = message.chan2_raw
        rc_channel_3 = message.chan3_raw
        rc_channel_4 = message.chan4_raw

        # Print the RC channel values received from TELEM1
        print("RC Channel 1 (from TELEM1):", rc_channel_1)
        print("RC Channel 2 (from TELEM1):", rc_channel_2)
        print("RC Channel 3 (from TELEM1):", rc_channel_3)
        print("RC Channel 4 (from TELEM1):", rc_channel_4)

The output that I get is

Hi @Kolappan ,

You can use the code below for reading the message that you’ve requested:

def get_requested_data(master, message_name: str, dict_key: str, value_unit: str, save_name: str):

    try:

        message_index = 0

        dict1 = master.recv_match(type= message_name, blocking=True, timeout=0.1).to_dict()

        dict_value = dict1[dict_key]

       

        toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit

        with open(save_name, 'a') as file:

            file.write(toWrite)

            file.write('\n')  

            message_index += 1

    except:

        pass

If you just want to monitor the data on Terminal instead of saving it to a file, you can go with deleting the lines below and simply use a print function:

toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit

        with open(save_name, 'a') as file:

            file.write(toWrite)

            file.write('\n')  

            message_index += 1

And here is the example usage of the loop code:

request_message_interval(master, "VFR_HUD", 1)

while True:

    try:

        get_requested_data(master, "VFR_HUD", 'alt', "m", save_name)

    except:

        pass

Thank you! This worked…

1 Like

Hi @toosat, @Kolappan,

I found this post searching on a way to print the result of a MAVLINK message on my Pymavlink terminal.
I’m not working on a sub but on a plane - you are gliding in the sea and me in the air, quite similar ! - with Pymavlink+Mavlink.
My goal is to have a Python script with multiples flight commands divided in parts, and these parts will be triggered by Mavlink like “Go high and right => trigger “Altitude 50m” => when Altitude is 50 meters go left and down”
So I’m thinking to use Mavlink message on altitude, request and print this data multiple time per minute, and when this “print” is “50” go to next commands.

Your ideas seems really great in this post, but I didn’t succeed unfortunatly. And I’m not as good as you are in Python scripting.

The data I want to use is:

POSITION_TARGET_GLOBAL_INT
https://mavlink.io/kr/messages/common.html#POSITION_TARGET_GLOBAL_INT

This one seems particularly interesting :

def request_message_interval(master, message_input: str, frequency_hz: float):
    message_name = "MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT " + message_input
    message_id = getattr(mavutil.mavlink, message_name)
    master.mav.command_long_send(master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0, message_id, 1e6/ frequency_hz, 0, 0, 0, 0, 0)
    print("Requested the message successfully.")


def get_requested_data(master, message_name: str, dict_key: str, value_unit: str, save_name: str):
    try:
        message_index = 0
        dict1 = master.recv_match(type= message_name, blocking=True, timeout=0.1).to_dict()
        dict_value = dict1[dict_key]

toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit
with open(save_name, 'a') as file:
            file.write(toWrite)
            file.write('\n')  
            message_index += 1

    except:
pass

error message receive :

python test.py
File “/home/scripts/test.py”, line 30
toWrite = “Message_Index, " + message_index + " :” + str(dict_value) + value_unit
SyntaxError: expected ‘except’ or ‘finally’ block

Many thanks for your help !
Nicolas

Hi @Nicolas_T ,
Thank you for your kind words.

Python is an identation based language. You just need to give it 2 tabs before the “pass” command.

Sorry for the short reply, i am in a little rush right now. LMK if you have further questions.

Best Regards.

Hi toosat,
Thanks for your answer. I write defirently the script based on “identation” and I’ve got that :slight_smile:

def request_message_interval(master, message_input: str, frequency_hz: float):
    message_name = "MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT " + message_input
    message_id = getattr(mavutil.mavlink, message_name)
    master.mav.command_long_send(master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0, message_id, 1e6/ frequency_hz, 0, 0, 0, 0, 0)
    print("Requested the message successfully.")


def get_requested_data(master, message_name: str, dict_key: str, value_unit: str, save_name: str):
    try:
        message_index = 0
        dict1 = master.recv_match(type= message_name, blocking=True, timeout=0.1).to_dict()
        dict_value = dict1[dict_key]

        toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit
        with open(save_name, 'a') as file:file.write(toWrite)
        file.write('\n')  
        message_index += 1
    except:
        pass

So no more error, but I think it doesn’t work because I don’t receive the message “Requested the message successfully.” write in your script.
Do I suppose to find this message in my WSL window (I’m on WSL/Linux Ubuntu) where I’ve got the mavproxy prompt (MANUAL>), or in the Mavproxy dedicated window (with “Serial ports” status …) ?

So if you’ve got any idea, many thanks !
Nic

Hi @Nicolas_T
Is this the whole part of the script you ran? Do you call the functions in a while loop? Under normal conditions, you should see the message outputs in a save file that you should have pre-named in the script. The save file will be created in the same file where your main script runs.

If you just want to monitor the data on the Terminal tab, you can refer to my previous replies on this topic.

The Reply

Best Regards.

My script:

#!/usr/bin/python3

import time
import math
from pymavlink import mavutil

# connect to the flight controller
master = mavutil.mavlink_connection('tcp:127.0.0.1:5762')

# wait for a heartbeat
master.wait_heartbeat()

# inform user
print("Connected to system:", master.target_system, ", component:", master.target_component)

#Arm
master.mav.command_long_send(
    master.target_system,
    master.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
    0, # confirmation
    1, # param1 (1 to indicate arm)
    0, # param2 (all other params meaningless)
    0, # param3
    0, # param4
    0, # param5
    0, # param6
    0) # param7

#wait until arming confirmed (can manually check with master.motors_armed())
print("Waiting for the vehicle to arm")
master.motors_armed_wait()
print('Armed!')

import time
wait_time = 10
time.sleep(wait_time)

def request_message_interval(master, message_input: str, frequency_hz: float):
    message_name = "MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT " + message_input
    message_id = getattr(mavutil.mavlink, message_name)
    master.mav.command_long_send(master.target_system, master.target_component, mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, 0, message_id, 1e6/ frequency_hz, 0, 0, 0, 0, 0)
    print("Requested the message successfully.")


def get_requested_data(master, message_name: str, dict_key: str, value_unit: str, save_name: str):
    try:
        message_index = 0
        dict1 = master.recv_match(type= message_name, blocking=True, timeout=0.1).to_dict()
        dict_value = dict1[dict_key]
        toWrite = "Message_Index, " + message_index + " :" + str(dict_value) + value_unit
        with open(save_name, 'a') as file:file.write(toWrite)
        file.write('\n')  
        message_index += 1
        request_message_interval(master, "VFR_HUD", 1)
    
        while True: 
            get_requested_data(master, "VFR_HUD", 'alt', "m", save_name)
    except:
        pass

Indentation is a nightmare with Python , but I continue working on this script as no more error now but no result. Maybe because I’m working on a simulation (SITL for Ardupilot), and VFR_HUD gives nothing