stephendade / mav_rp2040

MAVLink for the RP2040
19 stars 6 forks source link

Struggling to receive telem data and print specific data #1

Closed WilliamB2022 closed 1 year ago

WilliamB2022 commented 1 year ago

Afternoon,

I am using a pixhawk6C with a pico companion running circuitpython. I have no need to send data to the FC, only require to receive and print telem data. Specifically GPS. I have tried to use the code after converting a few imports to switch from Micro to Circuit.

I am struggling with line pkt.get_type (i believe) as when trying to print the raw pkt I am only receiving bad_data_objects.

Is there something im missing?

stephendade commented 1 year ago

I am struggling with line pkt.get_type (i believe) as when trying to print the raw pkt I am only receiving bad_data_objects.

That means the packets are not being decoded properly. Have you checked your flight controller is using the correct MAVLink version and baudrate?

Are you using ArduPilot or PX4? I've not tested this with PX4, so it's unknown if it'll work.

WilliamB2022 commented 1 year ago

thank you for your reply @stephendade , I can confirm I am using Ardupilot. Think I am struggling trying to work out how to request the data I need. Currently I am receiving heartbeats fine using your code however, when trying to specifically request VFR_HUD I cant seem to work out how to do this using the pymavminimal.

usually using mavlink I'd use request_message_interval and then use the message ID. Could you please if possible give an example of receiving anything other than the heartbeat?

stephendade commented 1 year ago

usually using mavlink I'd use request_message_interval and then use the message ID. Could you please if possible give an example of receiving anything other than the heartbeat?

The request_message_interval message isn't supported at this time. It'd have to be added to pymavminimal.py - basically copied from the Python MAVLink bindings.

It'll be a few weeks before I have time to add it. If you get around to it before me, happy to accept it as a PR.

WilliamB2022 commented 1 year ago

thats no problem @stephendade, whatever I can accomplish I will push by you for your consideration.

I have seen in the pymavminimal file that you do have the MAVLink Object and the MAVLink_messages of the current supported classes. With the current code as is, is there anyway to display the individual MessageId's?


# MAVLink
mavobj = pymav.MAVLink()
mavhud = pymav.MAVLink_message('74', 'VFR_HUD')
mavobj.robust_parsing = True

# Keep looping to receive data
while True:
    num = uart.read(100)
    if num is not None:
        mavhud.payload = num 
        hud_dict = mavhud.to_dict()
        print(hud_dict)

Currently, with that, I seem to only be receiving whatever i type as the ID name back into my Dict. I know for sure I am doing something wrong. Should I instead of using the MavLink_vfr_hud_message?

stephendade commented 1 year ago

Try:

# MAVLink
mavobj = pymav.MAVLink()
mavobj.robust_parsing = True

# Keep looping to receive data
while True:
    num = uart.read(100)
    if num is not None:
        rxData = uart0.read(num)
        pkts = mavobj.parse_buffer(bytearray(rxData))
        if pkts is not None:
            for pkt in pkts:
                print(pkt.get_msgId())

[Note I've not tested this ... might be syntax errors]

WilliamB2022 commented 1 year ago

That just returns '0's signaling its seeing the heartbeat. Think the problem may be that we are just letting the ardupilot send us its standard data packet. From previous things I've done I've had to request the data stream of the message ID that I need. It looks like you have all the ways of handling those messages within your pymavminimal, but no way of requesting the data to sent to them.

You are far more experienced than myself and I'm feeling like im missing something so simple haha

stephendade commented 1 year ago

Ahh, my misunderstanding. Yes, the flight controller will only send the heartbeat packets until requested to send additional messages.

You can request messages via the MAV_CMD_SET_MESSAGE_INTERVAL command. Here's a rough example:

#!/usr/bin/env python3

# The TELEM port should be set to MAVLink2, 57600 baud

from machine import Pin, UART
import time
import pymavminimal as pymav

led = Pin(25, Pin.OUT)

uart0 = UART(0, baudrate=57600, tx=Pin(0), rx=Pin(1))

seen_heartbeat = False

# MAVLink
mavobj = pymav.MAVLink()
mavobj.robust_parsing = True

# Keep looping to receive data
while True:
    num = uart0.any()
    # Receive data and process into MAVLink packets
    if num > 0:
        rxData = uart0.read(num)
        pkts = mavobj.parse_buffer(bytearray(rxData))
        if pkts is not None:
            for pkt in pkts:
                if pkt.get_type() == 'HEARTBEAT' and pkt.type not in [pymav.MAV_TYPE_GCS, pymav.MAV_TYPE_ADSB, pymav.MAV_TYPE_GIMBAL, pymav.MAV_TYPE_ONBOARD_CONTROLLER]:
                    led.toggle()
                    if not seen_heartbeat:
                        print("Got heartbeat from {0}:{1}".format(pkt.get_srcSystem(), pkt.get_srcComponent()))
                        mavobj.srcSystem = pkt.get_srcSystem()
                        mavobj.srcComponent = 158 #MAV_COMP_ID_PERIPHERAL
                        seen_heartbeat = True
                        # Send the set message interval request for VFR_HUD (74), once we have heard the first heartbeat
                        command = 511 #MAV_CMD_SET_MESSAGE_INTERVAL
                        param1 = 74 # Message ID MAVLINK_MSG_ID_VFR_HUD
                        param2 = 1 # Message interval
                        cmd = mavobj.command_long_encode(1, 1, command, 1, param1, param2, 0, 0, 0, 0, 0)
                        uart0.write(cmd.pack(mavobj))
                if pkt.get_type() == 'VFR_HUD':
                    print(pkt)
    time.sleep(0.01)
WilliamB2022 commented 1 year ago

Thank you so much for helping with this, I am very grateful! Seems there is no attribute 'mavobj.command_long_encode' within the MAVLink class though. Any guidance will be once again very well received.

WilliamB2022 commented 1 year ago

@stephendade Just managed it! please see below full code for my VFR_HUD in circuitpython if it can be of any use to anyone else looking

from microcontroller import Pin
import board
import busio
import time
import pymavminimal as pymav

uart = busio.UART(baudrate=57600, tx=board.GP12, rx=board.GP13)
seen_heartbeat = False

# MAVLink
mavobj = pymav.MAVLink()
mavobj.robust_parsing = True

# Keep looping to receive data
while True:
    num = uart.read(50)
    if num is not None:  
        pkts = mavobj.parse_buffer(bytearray(num))
        if pkts is not None:
            for pkt in pkts:
                if pkt.get_type() == 'HEARTBEAT' and pkt.type not in [pymav.MAV_TYPE_GCS, pymav.MAV_TYPE_ADSB, pymav.MAV_TYPE_GIMBAL, pymav.MAV_TYPE_ONBOARD_CONTROLLER]:
                    if not seen_heartbeat:
                        print("Got heartbeat from {0}:{1}".format(pkt.get_srcSystem(), pkt.get_srcComponent()))
                        mavobj.srcSystem = pkt.get_srcSystem()
                        mavobj.srcComponent = 158 #MAV_COMP_ID_PERIPHERAL
                        seen_heartbeat = True
                        # Send the set message interval request for VFR_HUD (74), once we have heard the first heartbeat
                        command = 511 #MAV_CMD_SET_MESSAGE_INTERVAL
                        param1 = 74 # Message ID MAVLINK_MSG_ID_VFR_HUD
                        param2 = 1 # Message interval
                        cmd = pymav.MAVLink_command_long_message(1, 1, command, 1, param1, param2, 0, 0, 0, 0, 0)
                        uart.write(cmd.pack(mavobj))
                if pkt.get_type() == 'VFR_HUD':
                    print(pkt)
    time.sleep(5)