Mission Upload using Pymavlink in Python3

Hello,
I am trying to upload mission using pymavlink from mission.txt file. The problem is - the code that I am using uploads mission perfectly on python 2.7 but gives error on python3

Code

from pymavlink import mavutil
from pymavlink import mavwp
import time

# Create the connection
# From topside computer

master = mavutil.mavlink_connection('tcp:192.168.0.21:5762')

master.wait_heartbeat()

wp = mavwp.MAVWPLoader()

def cmd_set_home(home_location, altitude):
    print('--- ', master.target_system, ',', master.target_component)
    master.mav.command_long_send(
        master.target_system, master.target_component,
        mavutil.mavlink.MAV_CMD_DO_SET_HOME,
        1, # set position
        0, # param1
        0, # param2
        0, # param3
        0, # param4
        home_location[0], # lat
        home_location[1], # lon
        altitude) 

def uploadmission(aFileName):
    home_location = None
    home_altitude = None

    with open(aFileName) as f:
        for i, line in enumerate(f):
            if i==0:
                if not line.startswith('QGC WPL 110'):
                    raise Exception('File is not supported WP version')
            else:   
                linearray=line.split('\t')
                ln_seq = int(linearray[0])
                ln_current = int(linearray[1])
                ln_frame = int(linearray[2])
                ln_command = int(linearray[3])
                ln_param1=float(linearray[4])
                ln_param2=float(linearray[5])
                ln_param3=float(linearray[6])
                ln_param4=float(linearray[7])
                ln_x=float(linearray[8])
                ln_y=float(linearray[9])
                ln_z=float(linearray[10])
                ln_autocontinue = float(linearray[11].strip())
                if(i == 1):
                    home_location = (ln_x,ln_y)
                    home_altitude = ln_z
                p = mavutil.mavlink.MAVLink_mission_item_message(master.target_system, master.target_component, ln_seq, ln_frame,
                                                                ln_command,
                                                                ln_current, ln_autocontinue, ln_param1, ln_param2, ln_param3, ln_param4, ln_x, ln_y, ln_z)
                wp.add(p)
                    
    cmd_set_home(home_location,home_altitude)
    msg = master.recv_match(type = ['COMMAND_ACK'],blocking = True)
    print(msg)
    print('Set home location: {0} {1}'.format(home_location[0],home_location[1]))
    time.sleep(1)

    #send waypoint to airframe
    master.waypoint_clear_all_send()
    master.waypoint_count_send(wp.count())

    for i in range(wp.count()):
        msg = master.recv_match(type=['MISSION_REQUEST'],blocking=True)
        print(msg)
        master.mav.send(wp.wp(msg.seq))
        print('Sending waypoint {0}'.format(msg.seq))


uploadmission('mission.txt')

mission.txt


QGC WPL 110
0	0	0	16	0.0	0.0	0.0	0.0	-35.3632621765	149.165237427	584.0	1
1	0	3	22	15.0	0.0	0.0	0.0	0.0	0.0	30.0	1
2	0	3	16	0.0	0.0	0.0	0.0	-35.3623428345	149.165100098	30.0	1
3	0	3	16	0.0	0.0	0.0	0.0	-35.3615036011	149.165084839	30.0	1
4	0	3	16	0.0	0.0	0.0	0.0	-35.3610038757	149.165756226	30.0	1
5	0	3	16	0.0	0.0	0.0	0.0	-35.3608703613	149.16708374	30.0	1
6	0	3	16	0.0	0.0	0.0	0.0	-35.361579895	149.168197632	30.0	1
7	0	3	16	0.0	0.0	0.0	0.0	-35.362651825	149.168319702	30.0	1
8	0	0	20	0.0	0.0	0.0	0.0	0.0	0.0	0.0	1
9	0	3	16	0.0	0.0	0.0	0.0	-35.3645172119	149.168655396	30.0	1
10	0	3	16	0.0	0.0	0.0	0.0	-35.3654441833	149.168228149	25.0	1
11	0	3	16	0.0	0.0	0.0	0.0	-35.3658027649	149.167251587	25.0	1
12	0	3	16	0.0	0.0	0.0	0.0	-35.3654708862	149.166061401	20.0	1
13	0	3	16	0.0	0.0	0.0	0.0	-35.3640899658	149.165374756	10.0	1
14	0	3	21	0.0	0.0	0.0	1.0	-35.3633384705	149.165252686	0.0	1

Everything that i’ve implemented on pymavlink in my code such as mission read, arm and takeoff works perfectly on both python 2.7 and python 3 but uploading mission shows error (only on python3) while packing mavlink message inside ardupilotmega.py (odd)

Error message.

COMMAND_ACK {command : 179, result : 0}
Set home location: -35.3632621765 149.165237427
MISSION_REQUEST {target_system : 255, target_component : 0, seq : 0}
Traceback (most recent call last):
  File "mission_upload.py", line 76, in <module>
    uploadmission('mission.txt')
  File "mission_upload.py", line 72, in uploadmission
    master.mav.send(wp.wp(msg.seq))
  File "/home/abhish/anaconda3/envs/new/lib/python3.6/site-packages/pymavlink/dialects/v10/ardupilotmega.py", line 13157, in send
    buf = mavmsg.pack(self, force_mavlink1=force_mavlink1)
  File "/home/abhish/anaconda3/envs/new/lib/python3.6/site-packages/pymavlink/dialects/v10/ardupilotmega.py", line 8812, in pack
    return MAVLink_message.pack(self, mav, 254, struct.pack('<fffffffHHBBBBB', self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z, self.seq, self.command, self.target_system, self.target_component, self.frame, self.current, self.autocontinue), force_mavlink1=force_mavlink1)
struct.error: required argument is not an integer

Can someone suggest me what am I doing wrong.
Thank you.

The autocontinue should be integer. i.e

ln_autocontinue = int(float(linearray[11].strip()))

This solves the problem.

1 Like