ArduPilot / pymavlink

python MAVLink interface and utilities
Other
497 stars 597 forks source link

in Python3, generator for 'char[n]' datatype is wrong #300

Open mfassler opened 5 years ago

mfassler commented 5 years ago

Hello,

I'm trying to run this code:

#!/usr/bin/env python3

import sys
if sys.version_info[0] < 3:
    raise Exception("Must be using Python 3")

import os

## TODO:  can this be an argument to dronekit.connect()?
os.environ['MAVLINK20'] = '1'

import dronekit
from dronekit import mavutil

#vehicle = dronekit.connect('/dev/ttyACM0,115200', baud=115200)
#vehicle = dronekit.connect('/dev/ttyUSB0,115200', baud=115200)
vehicle = dronekit.connect('127.0.0.1:14551')

tune_c_scale = b'MFT200L16<cdefgab>cdefgab>c'

#### This fails:
vehicle.play_tune(tune_c_scale)

#### This works:
msg = mavutil.mavlink.MAVLink_play_tune_message(0, 0, tune_c_scale, tune2=b'')
vehicle.send_mavlink(msg)

The command vehicle.play_tune() fails with the following error:

Traceback (most recent call last):
  File "testBug.py", line 23, in <module>
    vehicle.play_tune(tune_c_scale)
  File "/home/fassler/.local/lib/python3.7/site-packages/dronekit/__init__.py", line 2318, in play_tune
    self.send_mavlink(msg)
  File "/home/fassler/.local/lib/python3.7/site-packages/dronekit/__init__.py", line 2215, in send_mavlink
    self._master.mav.send(message)
  File "/home/fassler/.local/lib/python3.7/site-packages/dronekit/mavlink.py", line 146, in newsendfn
    return sendfn(mavmsg, *args, **kwargs)
  File "/home/fassler/.local/lib/python3.7/site-packages/pymavlink/dialects/v20/ardupilotmega.py", line 11709, in send
    buf = mavmsg.pack(self, force_mavlink1=force_mavlink1)
  File "/home/fassler/.local/lib/python3.7/site-packages/pymavlink/dialects/v20/ardupilotmega.py", line 10707, in pack
    return MAVLink_message.pack(self, mav, 187, struct.pack('<BB30s200s', self.target_system, self.target_component, self.tune, self.tune2), force_mavlink1=force_mavlink1)
struct.error: argument for 's' must be a bytes object

If I manually construct the message myself, specifying tune2=b'', it works.

I believe this is because the generator is interpreting the message datatype of char[200] as an array of 200 strings, like this: tune2=['', '', '', '' ... '', ''] which is incorrect for Python3.

If I set tune2=b'' then the struct.pack() statement seems to do the correct thing.

peterbarker commented 5 years ago

On Sun, 14 Apr 2019, Mark Fassler wrote:

If I set tune2=b'' then the struct.pack() statement seems to do the correct thing.

Here's what MAVProxy does (near enough to canonical use case at the moment...):

 def cmd_playtune(self, args):
     '''send PLAY_TUNE message'''
     if len(args) < 1:
         print("Usage: playtune TUNE")
         return
     tune = args[0]
     str1 = tune[0:30]
     str2 = tune[30:]
     if sys.version_info.major >= 3 and not isinstance(str1, bytes):
         str1 = bytes(str1, "ascii")
     if sys.version_info.major >= 3 and not isinstance(str2, bytes):
         str2 = bytes(str2, "ascii")
     self.master.mav.play_tune_send(self.settings.target_system,
                                    self.settings.target_component,
                                    str1, str2)

(from https://github.com/ardupilot/MAVProxy/blob/master/MAVProxy/modules/mavproxy_misc.py#L257)

alehed commented 2 years ago

The default argument for strings has been fixed in master. This issue can probably be closed.