alduxvm / pyMultiWii

MultiWii Serial Protocol (MSP) API to send and receive data from firmware using MSP
GNU General Public License v3.0
153 stars 84 forks source link

Running a Python 3 script #41

Open brightproject opened 4 months ago

brightproject commented 4 months ago

Hello @alduxvm, thanks for your work. This is not entirely an issue, perhaps someone has never encountered such a problem. I use WSL on Windows 10 to run Ubuntu.

py --version
Python 3.12.0

There I collect the firmware for betaflight from source code, and someone may use docker, but that’s not the point. So, I needed to get attitude angle data from the flight controller F411 NOXE V3 via the UART2. I got the code from here

https://github.com/alduxvm/pyMultiWii/blob/master/demo/show-attitude.py

But it didn’t want to work and gave an error. I had to change the code a little:

#except Exception,error:
except Exception as error:

After that, I could not determine the COM port, the command line always showed the message sendCMD... The solution to the problem was simple, because... I'm on Linux on WSL, then my ports are designated like this:

`COM1:` - `/dev/ttyS1`
`COM2:` - `/dev/ttyS2`
`COM3:` - `/dev/ttyS3`
...
`COM30:` - `/dev/ttyS30`

Information from here. As a result, the rewritten code for the COM15 port.

#!/usr/bin/env python

"""show-attitude.py: Script to ask the MultiWii Board attitude and print it."""

__author__ = "Aldo Vargas"
__copyright__ = "Copyright 2017 Altax.net"

__license__ = "GPL"
__version__ = "1.1"
__maintainer__ = "Aldo Vargas"
__email__ = "alduxvm@gmail.com"
__status__ = "Development"

from pymultiwii import MultiWii
from sys import stdout

if __name__ == "__main__":

    #board = MultiWii("/dev/ttyUSB0")
    #board = MultiWii("/dev/tty.SLAB_USBtoUART")
    #board = MultiWii("COM15")
    board = MultiWii("/dev/ttyS15")
    try:
        while True:
            board.getData(MultiWii.ATTITUDE)
            #print (board.attitude) #uncomment for regular printing

            # Fancy printing (might not work on windows...)
            message = "angx = {:+.2f} \t angy = {:+.2f} \t heading = {:+.2f} \t elapsed = {:+.4f} \t".format(float(board.attitude['angx']),float(board.attitude['angy']),float(board.attitude['heading']),float(board.attitude['elapsed']))
            stdout.write("\r%s" % message )
            stdout.flush()
            # End of fancy printing
    #except Exception,error:
    except Exception as error:
        print ("Error on Main: "+str(error))

I receive orientation angle data.

python3 show-attitude.py
Waking up board on /dev/ttyS15...
1
angx = +2.90     angy = +21.70   heading = +57.00        elapsed = +0.0100

show-attitude It works well!