Use Telemetry without a Mission Planner

I am using 3dr telemetry, I was able to send and receive the data from it using MP, but what if I have my own mission planner, and I want to send and receive data? How can I do that ?

I am creating a python code, which will receive data from the copter through telemetry and also send the data. I know the messages will be in the format of MAVLINK. Is there any specific API for that ?

Did you have a look at GitHub - ArduPilot/pymavlink: python MAVLink interface and utilities

1 Like

Can I use ROS for that as I didnt find any topic.
Moreover, I was trying to implement pymavlink

import time
from pymavlink import mavutil

class Commns:
    def __init__(self, device, baud):
        self.device = device
        self.baud = baud
        self.connection = None

    def connect(self):
        try:
            self.connection = mavutil.mavlink_connection(self.device, baud=self.baud)
            self.connection.wait_heartbeat()
            print("Heartbeat from system (system %u component %u)" % (
            self.connection.target_system, self.connection.target_component))
        except Exception as e:
            print("Error connecting to Pixhawk:", str(e))

    def close(self):
        if self.connection:
            self.connection.close()
            print("Connection closed.")

if __name__ == "__main__":
    device = '/dev/ttyUSB0'  # Adjust this to the appropriate device name
    baud = 115200  # Typical baud rate for telemetry radios
    # Create an instance of PixhawkConnector
    connector = Commns(device, baud)
    # Connect to Pixhawk
    connector.connect()
    # Do other tasks here...
    # Close the connection when done
    connector.close()

If I want to check my code on SITL what baud rate and device/port should be use ?

change device to ‘tcp:localhost:5762’ and you should be good. Port 5760 is normally SERIAL0 which Mission Planner will connect to when you start SITL, port 5762 is SERIAL1

You can use MAVROS if you’re using ROS

import time
from pymavlink import mavutil


class Connection:
    # The connection class is used to connect the vehicle,
    # further, more the class can also connect wit sitl for simulation and debug purposes.
    def __init__(self):
        self.connection = None
        self.device = None
        self.baud = None
        self.connection_string = None

    def init(self, device, baud):
        # To connect with telemetry/devices
        self.device = device
        self.baud = baud

    def init_sitl(self, connection_string):
        # to connect with software in the loop
        self.connection_string = connection_string


    def connect(self):
        try:
            self.connection = mavutil.mavlink_connection(self.device, baud=self.baud)
            self.connection.wait_heartbeat()
            print("Heartbeat from system (system %u component %u)" % (
            self.connection.target_system, self.connection.target_component))
        except Exception as e:
            print("Error connecting to Flight Controller:", str(e))

    def connect_sitl(self):
        try:
            self.connection = mavutil.mavlink_connection(self.connection_string)
            self.connection.wait_heartbeat()
            print("Heartbeat from system (system %u component %u)" % (
            self.connection.target_system, self.connection.target_component))
        except Exception as e:
            print("Error connecting to Flight Controller:", str(e))

    def get_instance(self):
        return self.connection

    def close(self):
        if self.connection:
            self.connection.close()
            print("Connection closed.")


class FlightController:
    # Following class is used to perform the basic functions of vehicle
    def __init__(self, vehicle):
        self.vehicle = vehicle

    def turn_on_motor(self):
        # arm the motors
        self.vehicle.arducopter_arm()
        self.vehicle.motors_armed_wait()
        print("Turning on Motors")



    def turn_off_motor(self):
        # disarm the motors
        self.vehicle.arducopter_disarm()
        self.vehicle.motors_disarmed_wait()
        print("Turning off Motors")

    def set_mode(self, mode):
        # function to set the vehicle mode (i-e guided auto rtl etc)
        mode_id = self.vehicle.mode_mapping()[mode]
        self.vehicle.set_mode_apm(mode_id)
        while True:
            ack = self.vehicle.recv_match(type='COMMAND_ACK', blocking=True, timeout=10)
            if ack and ack.command == mavutil.mavlink.MAV_CMD_DO_SET_MODE and ack.result == mavutil.mavlink.MAV_RESULT_ACCEPTED:
                print("{} mode set successfully...".format(mode))
                break

    # Function to land the vehicle
    def land_vehicle(self):
        self.set_mode('LAND')
        print("Landing...")

    # Function to trigger Return to Launch (RTL)
    def rtl_vehicle(self):
        self.set_mode('RTL')
        print("Returning to Launch...")

    # Function to take off
    def takeoff(self,altitude=5):
        # Command the vehicle to take off
        self.vehicle.mav.command_long_send(
            self.vehicle.target_system,
            self.vehicle.target_component,
            mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
            0,
            0, 0, 0, 0, 0, 0, altitude
        )




if __name__ == "__main__":
    try:
        device = 'com8'  # port
        baud = 115200  # baud
        connecting_string = 'tcp:127.0.0.1:5762'  # sitl connecting sting
        connector = Connection()
        connector.init_sitl(connecting_string)
        connector.connect_sitl()
        flight_controller = FlightController(connector.get_instance())
        flight_controller.turn_on_motor()
        flight_controller.set_mode('GUIDED')
        flight_controller.takeoff()

    except Exception as e:
        print("Exception", e)

I am unable to takeoff in sitll ?

COMMAND_ACK {command : 22, result : 4, progress : 0, result_param2 : 0, target_system : 255, target_component : 0}

when I execute

 ack = self.vehicle.recv_match(type='COMMAND_ACK', blocking=True, timeout=10)

I tried your code but just swapped the order in which you send the commands and it works:

    flight_controller = FlightController(connector.get_instance())
    flight_controller.set_mode('GUIDED')
    flight_controller.turn_on_motor()
    flight_controller.takeoff()

So first setting the mode and then arming the motors

Thanks it works. There is one more thing which is confusing me a little.
I want to make a waypoint mission, I know I have to use MAV_CMD_NAV_WAYPOINT, a list of waypoints will be created with this, and auto mode will be use to start waypoint mission.

What I don’t know is that how to upload the data in the flight controller, is there sample template you can tell me or guided?

I haven’t done waypoint uploads with Python before, but there are a sequence of steps to follow which is described here: Mission Protocol · MAVLink Developer Guide

I have written the code, for waypoint mission using pymavlink, which is working.

class Waypoint:
    def __init__(self, vehicle):
        self.vehicle = vehicle
        self.target_locations = None

    def init_target_locations(self, target_locations):
        self.target_locations = target_locations

        msg = dialect.MAVLink_mission_count_message(target_system=self.vehicle.target_system,
                                                    target_component=self.vehicle.target_component,
                                                    count=len(target_locations) + 2,
                                                    mission_type=dialect.MAV_MISSION_TYPE_MISSION)
        self.vehicle.mav.send(msg)
        # catch a message
        message = self.vehicle.recv_match(blocking=True)
        # convert this message to dictionary
        message = message.to_dict()
        # check this message is MISSION_REQUEST
        if message["mavpackettype"] == dialect.MAVLink_mission_request_message.msgname:
            # check this request is for mission items
            if message["mission_type"] == dialect.MAV_MISSION_TYPE_MISSION:
                # get the sequence number of requested mission item
                seq = message["seq"]
                # create mission item int message
                if seq == 0:
                    # create mission item int message that contains the home location (0th mission item)
                    message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
                                                                       target_component=self.vehicle.target_component,
                                                                       seq=seq,
                                                                       frame=dialect.MAV_FRAME_GLOBAL,
                                                                       command=dialect.MAV_CMD_NAV_WAYPOINT,
                                                                       current=0,
                                                                       autocontinue=0,
                                                                       param1=0,
                                                                       param2=0,
                                                                       param3=0,
                                                                       param4=0,
                                                                       x=0,
                                                                       y=0,
                                                                       z=0,
                                                                       mission_type=dialect.MAV_MISSION_TYPE_MISSION)

                # send takeoff mission item
                elif seq == 1:

                    # create mission item int message that contains the takeoff command
                    message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
                                                                       target_component=self.vehicle.target_component,
                                                                       seq=seq,
                                                                       frame=dialect.MAV_FRAME_GLOBAL_RELATIVE_ALT,
                                                                       command=dialect.MAV_CMD_NAV_TAKEOFF,
                                                                       current=0,
                                                                       autocontinue=0,
                                                                       param1=0,
                                                                       param2=0,
                                                                       param3=0,
                                                                       param4=0,
                                                                       x=0,
                                                                       y=0,
                                                                       z=target_locations[0][2],
                                                                       mission_type=dialect.MAV_MISSION_TYPE_MISSION)

                # send target locations to the vehicle
                else:

                    # create mission item int message that contains a target location
                    message = dialect.MAVLink_mission_item_int_message(target_system=self.vehicle.target_system,
                                                                       target_component=self.vehicle.target_component,
                                                                       seq=seq,
                                                                       frame=dialect.MAV_FRAME_GLOBAL_RELATIVE_ALT,
                                                                       command=dialect.MAV_CMD_NAV_WAYPOINT,
                                                                       current=0,
                                                                       autocontinue=0,
                                                                       param1=0,
                                                                       param2=0,
                                                                       param3=0,
                                                                       param4=0,
                                                                       x=int(target_locations[seq - 2][0] * 1e7),
                                                                       y=int(target_locations[seq - 2][1] * 1e7),
                                                                       z=target_locations[seq - 2][2],
                                                                       mission_type=dialect.MAV_MISSION_TYPE_MISSION)

                # send the mission item int message to the vehicle
                self.vehicle.mav.send(message)
        # check this message is MISSION_ACK
        elif message["mavpackettype"] == dialect.MAVLink_mission_ack_message.msgname:
            # check this acknowledgement is for mission and it is accepted
            if message["mission_type"] == dialect.MAV_MISSION_TYPE_MISSION and \
                    message["type"] == dialect.MAV_MISSION_ACCEPTED:
                # break the loop since the upload is successful
                print("Mission upload is successful")


if __name__ == "__main__":
    try:
        connector = Connection()
        # device = 'com8'  # port
        # baud = 115200  # baud
        # connector.init(device, baud)
        # connector.connect_telemetry()
        connecting_string = 'tcp:127.0.0.1:5762'  # sitl connecting sting
        connector.init_sitl(connecting_string)
        connector.connect_sitl()
        flight_controller = FlightController(connector.get_instance())
        waypoint_mission = Waypoint(connector.get_instance())
        flight_controller.get_parameter_value('AUTO_OPTIONS')
        flight_controller.set_parameter_value('AUTO_OPTIONS', 3, mavutil.mavlink.MAV_PARAM_TYPE_UINT8)
        flight_controller.set_mode('GUIDED')
        flight_controller.get_mode()
        flight_controller.turn_on_motor()
        flight_controller.takeoff()
        target_locations = ((-35.361297, 149.161120, 50.0),
                            (-35.360780, 149.167151, 50.0),
                            (-35.365115, 149.167647, 50.0),
                            (-35.364419, 149.161575, 50.0))
        waypoint_mission.init_target_locations(target_locations)
        flight_controller.set_mode('AUTO')
        gps = GPS(connector.get_instance())
        gps.gps_3d_location()

        # compass = Compass(connector.get_instance())
        # compass.get_heading()

    except Exception as e:
        print("Exception", e)

there is one more guidance I need, how to set a flag for waypoint reach and how can I add actions in it?