How to send Global position as mavlink via serial port?

Hello,

I am trying to feed drone’s global position into a antenna tracker “Crossbow mini”.
According to the manual, the tracker can read

Crossbow AAT needs both these 2 MAVLink messages to track.
MAVLINK_MSG_ID_GPS_RAW_INTMAVLINK_MSG_ID_GLOBAL_POSITION_INT

I can get drone’s lat, long and altitude AGL as ROS message
So I would like to convert these data into mavlink message and send via serial port.
How can I achieve this?
Any suggestions would be much appreciated.

Kyu

To answer my question myself.

This was done by using pymavlink.
Pymavlink can be installed by pip.

from pymavlink import mavutil

port = '/dev/ttyUSB0'
baud_rate = 38400
mav = mavutil.mavlink_connection(port, baud=baud_rate)

def send_gps_raw_int(self, latitude, longitude, altitude):
        print(f"gps_raw_int: \t\tlat:{latitude}, \tlng:{longitude}")
        self.mav.mav.gps_raw_int_send(
            int(time.time() * 1e6),  # time_usec
            3,  # fix_type (3 = 3D fix)
            int(latitude),  # lat (degrees * 1e7)
            int(longitude),  # lon (degrees * 1e7)
            int(altitude * 1000),  # alt (mm)
            0,  # eph 
            0,  # epv 
            0,  # vel 
            0,  # cog 
            18  # satellites_visible 
        )
def send_global_position_int(self, latitude, longitude, altitude, relative_alt):
        print(f"global_position_int: \tlat:{latitude}, \tlng:{longitude}, \talt:{altitude}")
        self.mav.mav.global_position_int_send(
            int(time.time() * 1e3)% 4294967295,  # time_boot_ms 
            int(latitude),  # lat (degrees * 1e7)
            int(longitude),  # lon ( degrees * 1e7)
            int(altitude * 1000),  # alt ( mm )
            int(relative_alt * 1000),  # relative_alt (mm )
            0,  # vx (NED , cm/s )
            0,  # vy (NED , cm/s )
            0,  # vz (NED , cm/s )
            0  # hdg (, cdeg )
        )
1 Like

Another option for you. You could just steal mav messages from QGC forward then send them from there either via bluetooth or serial. Id do it like this:

import time
from pymavlink import mavutil

# MAVLink connection settings
udp_ip = "localhost"
udp_port = 12345
serial_port = '/dev/ttyUSB0'
baud_rate = 38400

# Establish UDP connection to receive MAVLink messages
udp_conn = mavutil.mavlink_connection(f'udp:{udp_ip}:{udp_port}')

# Establish serial connection to forward MAVLink messages
serial_conn = mavutil.mavlink_connection(serial_port, baud=baud_rate)

# Function to receive and forward MAVLink messages
def receive_and_forward():
    while True:
        # Receive a message from the UDP connection
        msg = udp_conn.recv_msg()
        if msg:
            # Print received message
            print(f"Received message: {msg}")

            # Filtering specific message types
            if msg.get_type() == 'GPS_RAW_INT':
                print(f"Processing GPS_RAW_INT message: {msg}")
                # Forward the GPS_RAW_INT message
                serial_conn.mav.send(msg)
            elif msg.get_type() == 'GLOBAL_POSITION_INT':
                print(f"Processing GLOBAL_POSITION_INT message: {msg}")
                # Forward the GLOBAL_POSITION_INT message
                serial_conn.mav.send(msg)
            else:
                print(f"Ignored message type: {msg.get_type()}")

if __name__ == "__main__":
    try:
        receive_and_forward()
    except KeyboardInterrupt:
        print("Terminating script.")

or if you wanted to send everything:

import time
from pymavlink import mavutil

# MAVLink connection settings
udp_ip = "localhost"
udp_port = 12345
serial_port = '/dev/ttyUSB0'
baud_rate = 38400

# Establish UDP connection to receive MAVLink messages
udp_conn = mavutil.mavlink_connection(f'udp:{udp_ip}:{udp_port}')

# Establish serial connection to forward MAVLink messages
serial_conn = mavutil.mavlink_connection(serial_port, baud=baud_rate)

# Function to receive and forward MAVLink messages
def receive_and_forward():
    while True:
        # Receive a message from the UDP connection
        msg = udp_conn.recv_msg()
        if msg:
            # Print received message
            print(f"Received message: {msg}")

            # Forward the message via serial connection
            serial_conn.mav.send(msg)
            print(f"Forwarded message: {msg}")

if __name__ == "__main__":
    try:
        receive_and_forward()
    except KeyboardInterrupt:
        print("Terminating script.")

2 Likes

Then you dont need something like mavrouter on the ground, etc

Hi @ryanjAA
Thanks for sharing such a great code! :wink:

1 Like

No prob, let me know how it goes. I have one of those sitting around and was meaning to get it working.

@Kyuhyong_You another thought, id make sure to turn off auto-connect in qgc or it will connect to the serial adapter before sending data out (unless you were running it first but the script won’t run without the serial adapter connected).

When I get a sec I’m going to make an auto Bluetooth bridge so it sends from qgc to the script and picks it up via Bluetooth and sends to another bt module at the tracker. A set of hc05 linked as and via transparent serial will do the trick then it’s all wireless.

Another note. Probably just need parts of this integrated into QGC. Kind of like how you can run ardu tracker code on any fmu and then view it in mission planner. Then we can have pointing direction and toggles for beam width built in with different radiation patterns so you know they are covered, etc. (and if we could control an offset that would be great which we could hack without touching the crossbow code by offsetting lat/lon coordinates going out…).

Hi @Kyuhyong_You , I have a question if you can help:

I developed a machine learning SW to control a gimbal camera and all is good but I want to send the GPS data to the companion computer to send it to gimbal camera for target coordinates capturing by the gimbal it self. The gimbal have small LRF that measure distance & also GPS coordinates and to be able to get the target coordinates I must send the drone GPS data to companion computer and from there send it to gimbal. My question how I can do that please?

Thanks

Hi @Falcon
How the CC is connected to the FC?

  1. Using mavlink, you will need to figure out how to receive gps position from FC and send gimbal control message back to the FC.

  2. Using ROS, you can make a ROS node to listen to GPS position message from FC and send gimbal control message back to FC.

Hi @Kyuhyong_You

The CC is not connected to FC at the current setup since I’m not using the CC to control the vehicle or anything related to it. It’s just for image processing and command & control of the gimbal camera.

The camera is connect to the CC via IP connection (Ethernet).

The gimbal manufacturer have told me I can
Send the GPS info to the camera by following command MAVLINK_MSG_ID_GLOBAL_POSITION_INT
Only need to forward this message to the gimbal camera payload, but I want to understand how to achieve this.

thanks

If the CC is not connected to FC, there is no way to get GPS position data from FC unless CC has separate GPS sensor.