Coder Social home page Coder Social logo

ardupilot / pymavlink Goto Github PK

View Code? Open in Web Editor NEW
467.0 52.0 580.0 8.02 MB

python MAVLink interface and utilities

License: Other

Python 60.08% C 13.39% Makefile 0.24% C++ 4.62% Shell 0.86% C# 2.00% Java 1.61% JavaScript 11.57% Swift 4.61% PureBasic 0.10% Ada 0.93%

pymavlink's Introduction

Build Status

Pymavlink

This is a Python implementation of the MAVLink protocol. It includes a source code generator (generator/mavgen.py) to create MAVLink protocol implementations for other programming languages as well. Also contains tools for analyzing flight logs.

Documentation

Please see http://ardupilot.org/dev/docs/mavlink-commands.html for mavlink command reference.

For realtime discussion please see the pymavlink Gitter channel

Examples can be found in the repository or in the ArduSub book

Installation

Pymavlink supports both Python 2 and Python 3.

The following instructions assume you are using Python 3 and a Debian-based (like Ubuntu) installation.

.. note::

pymavlink assumes the command "python" is in your path. Your distribution may provide a package such as "python-is-python3" to ensure that "python" is in your path.

Dependencies

Pymavlink has several dependencies :

- [future](http://python-future.org/) : for Python 2 and Python 3 interoperability
- [lxml](http://lxml.de/installation.html) : for checking and parsing xml file 

Optional :

- numpy : for FFT
- pytest : for tests

On Linux

lxml has some additional dependencies that can be installed with your package manager (here with apt-get) :

.. note::

If you continue to use Python 2 you may need to change package names here (e.g. python3-numpy => python-numpy)

sudo apt-get install libxml2-dev libxslt-dev

Optional for FFT scripts and tests:

sudo apt-get install python3-numpy python3-pytest

Using pip you can install the required dependencies for pymavlink :

sudo python -m pip install --upgrade future lxml

On Windows

Use pip to install future as for Linux. Lxml can be installed with a Windows installer from here : https://pypi.org/project/lxml

Installation

For users

It is recommended to install pymavlink from PyPI with pip, that way dependencies should be auto installed by pip.

sudo python -m pip install --upgrade pymavlink

Mavnative

Starting from September 2022, mavnative, a C extension for parsing mavlink, was deprecated and removed. Mavnative development was stalled for long time, it only supports MAVLink1 and doesn't get any fix on the protocol.

For developers

From the pymavlink directory, you can use :

sudo MDEF=PATH_TO_message_definitions python -m pip install . -v

Since pip installation is executed from /tmp, it is necessary to point to the directory containing message definitions with MDEF. MDEF should not be set to any particular message version directory but the parent folder instead. If you have cloned from mavlink/mavlink then this is /mavlink/message_definitions . Using pip should auto install dependencies and allow you to keep them up-to-date.

Or:

sudo python setup.py install

Ardupilot Custom Modes

By default, pymavlink will map the Ardupilot mode names to mode numbers per the definitions in the ardupilotmega.xml file. However, during development, it can be useful to add to or update the default mode mappings.

To do this:

  • create a folder named .pymavlink in your home directory (i.e. $HOME on Linux, $USERPROFILE on Windows); and
  • add a JSON file called custom_mode_map.json to this new .pymavlink folder.

The JSON file is a dictionary that maps vehicle MAV_TYPE value to a dictionary of mode numbers to mode names. An example that duplicates the existing mapping for MAV_TYPE_FIXED_WING (enum value of 1) vehicles is as follows:

{
    "1": {
        "0":  "MANUAL",
        "1":  "CIRCLE",
        "2":  "STABILIZE",
        "3":  "TRAINING",
        "4":  "ACRO",
        "5":  "FBWA",
        "6":  "FBWB",
        "7":  "CRUISE",
        "8":  "AUTOTUNE",
        "10": "AUTO",
        "11": "RTL",
        "12": "LOITER",
        "13": "TAKEOFF",
        "14": "AVOID_ADSB",
        "15": "GUIDED",
        "16": "INITIALISING",
        "17": "QSTABILIZE",
        "18": "QHOVER",
        "19": "QLOITER",
        "20": "QLAND",
        "21": "QRTL",
        "22": "QAUTOTUNE",
        "23": "QACRO",
        "24": "THERMAL"
    }
}

This custom_mode_map.json file can be used to:

  • change the display name of an existing mode (e.g. change "TAKEOFF" to "LAUNCH");
  • add a new mode (e.g. add "25": "NEW_MODE"); and
  • add a mapping for an unsupported vehicle type (e.g. add a mapping for MAV_TYPE_AIRSHIP (enum value of 7) vehicles).

Notes:

  • Whilst the MAV_TYPE and mode numbers are integers, they need to be defined as strings in the JSON file, as raw integers can't be used as dictionary keys in JSON.
  • This feature updates the default definitions. You can use it to change the name-to-number mapping for a mode, but you completely can't remove an existing mapping.

License


pymavlink is released under the GNU Lesser General Public License v3 or later.

The source code generated by generator/mavgen.py is available under the permissive MIT License.

pymavlink's People

Contributors

alehed avatar amilcarlucas avatar andreasantener avatar andyp1per avatar arthurbenemann avatar dagoodma avatar davidbuzz avatar dependabot[bot] avatar geeksville avatar hamishwillee avatar iampete1 avatar jgoppert avatar julianoes avatar kd0aij avatar khancyr avatar lorenzmeier avatar magicrub avatar malife avatar mday299 avatar modnovolyk avatar mpaperno avatar nexton-winjeel avatar peterbarker avatar philipoe avatar pixhawk-students avatar shancock884 avatar squilter avatar thomasgubler avatar tridge avatar vooon avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

pymavlink's Issues

Python interface for custom dialect

I am able to generate the needed files for MAVLink in C with only a few custom messages (no common etc.).
However, for Python I can't get the same routine to work. I can generate the .py file with my messages, but I still want to utilize some functions from mavutils. How do I achieve this?
I.e. opening a serial interface and only utilizing say 2 custom messages.

False generation of mavlink headers (with bad XML input)

I noticed incorrect .h header file generation while using mavgenerate.py with my custom XML file. The message when looks like the following generates incomplete/incorrect .h file

<message id="500" name="TEST_MESSAGE">
	<field type="uint16_t" name="data1">Some data </field>
	<field type="uint16_t" name=""></field>
	<field type="uint16_t" name="data3"></field>
    </message> 

Please note the name for the 2nd field above is missing (name=""). The struct generated is:

MAVPACKED(
typedef struct __mavlink_test_message_t {
 uint16_t data1; /*< The number of packets received during */
 uint16_t ; /*< */
 uint16_t data3; /*< */
}) mavlink_test_message_t;

Intuitively, the user would assume the mavgenerate.py to throw an error. It took me a while to spot that the C compiler was unhappy about this silly error (I introduced when creating the XML), when the compiler was pointing at something entirely different.

PS: Also as reported and closed in mavlink repo and redirected to be resolved in pymavlink.

Unable to install pymavlink on Ubuntu 16.04

I successfully installed all the dependencies, but when trying to install with sudo pip2 install -U pymavlink I get:

Collecting pymavlink
Using cached pymavlink-2.2.0.tar.gz
Requirement already up-to-date: future in ./.local/lib/python2.7/site-packages (from pymavlink)
Requirement already up-to-date: lxml in ./.local/lib/python2.7/site-packages (from pymavlink)
Building wheels for collected packages: pymavlink
Running setup.py bdist_wheel for pymavlink ... error
Complete output from command /usr/bin/python -u -c "import setuptools, tokenize;file='/tmp/pip-build-D1ZhFK/pymavlink/setup.py';f=getattr(tokenize, 'open', open)(file);code=f.read().replace('\r\n', '\n');f.close();exec(compile(code, file, 'exec'))" bdist_wheel -d /tmp/tmpXSxTnnpip-wheel- --python-tag cp27:
running bdist_wheel
running build
running build_py
No XML message definitions found


Failed building wheel for pymavlink
Running setup.py clean for pymavlink
Failed to build pymavlink
Installing collected packages: pymavlink
Running setup.py install for pymavlink ... error
Complete output from command /usr/bin/python -u -c "import setuptools, tokenize;file='/tmp/pip-build-D1ZhFK/pymavlink/setup.py';f=getattr(tokenize, 'open', open)(file);code=f.read().replace('\r\n', '\n');f.close();exec(compile(code, file, 'exec'))" install --record /tmp/pip-ITjw7D-record/install-record.txt --single-version-externally-managed --compile:
running install
running build
running build_py
No XML message definitions found
----------------------------------------

Command "/usr/bin/python -u -c "import setuptools, tokenize;file='/tmp/pip-build-D1ZhFK/pymavlink/setup.py';f=getattr(tokenize, 'open', open)(file);code=f.read().replace('\r\n', '\n');f.close();exec(compile(code, file, 'exec'))" install --record /tmp/pip-ITjw7D-record/install-record.txt --single-version-externally-managed --compile" failed with error code 1 in /tmp/pip-build-D1ZhFK/pymavlink/

Any help would be appreciated!

Installing pymavlink on Ubuntu 16.04 fails

I tried to install pymavlink with pip:
sudo pip2 install -U pymavlink
No error message.
Trying to import mavutil
import mavutil
first gives the error message "module not found"
If I add the following line to my .bashrc file:

export PYTHONPATH="${PYTHONPATH}:/usr/local/lib/python2.7/dist-packages/pymavlink"

and try to import mavutil I get a different error message:

In [1]: import mavutil
---------------------------------------------------------------------------
ValueError                                Traceback (most recent call last)
<ipython-input-1-062bfe057715> in <module>()
----> 1 import mavutil

/usr/local/lib/python2.7/dist-packages/pymavlink/mavutil.py in <module>()
    105 
    106 # Set the default dialect. This is done here as it needs to be after the function declaration
--> 107 set_dialect(os.environ['MAVLINK_DIALECT'])
    108 
    109 class mavfile(object):

/usr/local/lib/python2.7/dist-packages/pymavlink/mavutil.py in set_dialect(dialect)
     80     '''
     81     global mavlink, current_dialect
---> 82     from .generator import mavparse
     83     if 'MAVLINK20' in os.environ:
     84         wire_protocol = mavparse.PROTOCOL_2_0

ValueError: Attempted relative import in non-package

Any idea?

Issue running this code

Whenever I try to run this code I am receiving this error.
Need exactly one type when dumping csv from bin file.

Not sure what it means by type? I am using bin file from a pixhawk sd card and typing this in the cmd
python mavlogdump.py data.bin --format "csv"

Multiple definition of element 'field' causes the content model to become ambiguous

=> pymavlink / generator / mavschema.xsd

Issue stems from the use of the 'extensions' element within a message definition:







The problem is that if a person were to deserialize into an object generated from the XSD the notion of 'extension' fields would be lost as the 'extensions' element does not actually define [contain] the extensions. It's a design smell to couple elements this way; instead the 'extended fields' should be children of the 'extensions' element.

While we're here, were can I find information as to how 'extensions' should be processed? When can they be excluded from content? Impacts with regards to CRC? etc...

Support UDP broadcast bus

I'd like to run a mavproxy that allows multiple DroneKit clients to connect simultaneously.

But mavudp.write() `locks on' to the last peer address:

                if self.last_address and self.broadcast:
                    self.destination_addr = self.last_address
                    self.broadcast = False
                    self.port.connect(self.destination_addr)

I'm tempted to just remove that block from mavudp.write(); I gather that allows for a race to be created between, for example, parallel waypoint loads....

Is there a cleaner way of doing this?

Is there likely to be any existing code that this change would break? If I understand this correctly, such code would need to be multiple peers operating as fallbacks for each other since they can't actually operate simultaneously; I'm not really sure in what scenarios that fallback pattern is actually usable, if any....

future module error

While running the sim_vehicle.py I'm getting this error message.

[4/4] Processing modules/mavlink/message_definitions/v1.0/ardupilotmega.xml
Traceback (most recent call last):
File "/home/medhijk/ardupilot/modules/mavlink/pymavlink/tools/mavgen.py", line 16, in
from pymavlink.generator import mavgen
File "/home/medhijk/ardupilot/modules/mavlink/pymavlink/generator/mavgen.py", line 12, in
from future import standard_library
ImportError: No module named future

mavgen returned 1 error code
Waf: Leaving directory `/home/medhijk/ardupilot/build/sitl'
Build failed
-> task in 'mavlink' failed (exit status 1):
{task 139927157712448: mavgen ardupilotmega.xml -> }
''
SIM_VEHICLE: Build failed
SIM_VEHICLE: Killing tasks

I thought it's missing the future module and so tried installing future by this command:
pip install future
But I get a message from the terminal as:
Requirement already satisfied: future in /usr/local/lib/python3.5/dist-packages

Can anyone suggest a way out of this?

Error module future

Hi,
When building sitl:

Traceback (most recent call last):
File "/home/x/ardupilot/modules/mavlink/pymavlink/tools/mavgen.py", line 16, in
from pymavlink.generator import mavgen
File "/home/x/ardupilot/modules/mavlink/pymavlink/generator/mavgen.py", line 12, in
from future import standard_library
ImportError: No module named future

proper git tags for releases

now that pymavlink is out of mavlink/mavlink can we start git tagging the releases?, it makes life a bit easier

MAV_CMD_DO_SET_SERVO using pymavlink

I have to use MAV_CMD_DO_SET_SERVO mavlink command in pymavlink for controlling a fixed wing UAV. Is there any syntax available. I tried channeloverride in dronekit python and its working. since i want to put my own control algorithm in a companion computer and many advised not to use channeloverride i want to use MAV_CMD_DO_SET_SERVO.

Pip install fails

I have no luck installing the package as described in the README:

sudo pip install .
Processing /home/julianoes/src/pymavlink
Requirement already satisfied (use --upgrade to upgrade): future in /usr/lib/python3.5/site-packages (from pymavlink==2.0.9)
Requirement already satisfied (use --upgrade to upgrade): lxml in /usr/lib/python3.5/site-packages (from pymavlink==2.0.9)
Installing collected packages: pymavlink
  Running setup.py install for pymavlink ... error
    Complete output from command /usr/bin/python -u -c "import setuptools, tokenize;__file__='/tmp/pip-jk12x8xn-build/setup.py';exec(compile(getattr(tokenize, 'open', open)(__file__).read().replace('\r\n', '\n'), __file__, 'exec'))" install --record /tmp/pip-ted1c5dm-record/install-record.txt --single-version-externally-managed --compile:
    running install
    running build
    running build_py
    No XML message definitions found

This happens on Python2 and Python3.
I also tried to install pymavlink as part of mavlink (as a submodule) and saw the same error.

MAVLINK_CHECK_MESSAGE_LENGTH have a bug

@julianoes in mavlink_helpers.h, if we define MAVLINK_CHECK_MESSAGE_LENGTH and when migid is greater than 256,mavlink_message_lengths[256] array will overflow.

#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
#ifndef MAVLINK_MESSAGE_LENGTH
	static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
#endif
#endif
	case MAVLINK_PARSE_STATE_GOT_MSGID2:
		rxmsg->msgid |= c<<16;
		mavlink_update_checksum(rxmsg, c);
		status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
	        if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid))
		{
			_mav_parse_error(status);
			status->parse_state = MAVLINK_PARSE_STATE_IDLE;
			break;
                }
#endif
		break;

Memory leak in generated dialect code

Hi,
While working on the stand alone MAVCesium server @fnoop had identified that memory resources were continuing to be used. I eventually tracked down the cause to this code segment within pyMAVLink:
https://github.com/ArduPilot/pymavlink/blob/master/generator/mavgen_python.py#L526

33600756-1f414d24-d9a2-11e7-9004-f56532e35bef

Issue where the problem was identified: goodrobots/MAVCesium#34

The behavior we observed was the result of a bytearray being extended over and over again, taking up more and more memory over time.

The issue is that it is quite possible to always have a complete message waiting to be decoded when parse_char() is called. In this case the final else statement of parse_char() never gets ran and the buffer continues to grow.

        def parse_char(self, c):
            '''input some data bytes, possibly returning a new message'''
            self.buf.extend(c)
            self.total_bytes_received += len(c)
            .....
            .....
            if m != None:               # <---- this always returns true with a new message.
                self.total_packets_received += 1
                self.__callbacks(m)
            else:                            # <---- so this code never gets a chance to run, causing a memory leak.
                if self.buf_len() == 0 and self.buf_index != 0:
                    self.buf = bytearray()
                    self.buf_index = 0
            return m

Although the logic in that statement self.buf_len() == 0 and self.buf_index != 0 is true every time this method is called, self.buf and self.buf_index are never able to be reset... personally I think the else could be removed and we should be testing that condition every time that method is called. e.g.:

        def parse_char(self, c):
            '''input some data bytes, possibly returning a new message'''
            self.buf.extend(c)
            self.total_bytes_received += len(c)
            .....
            .....
            if m != None:
                self.total_packets_received += 1
                self.__callbacks(m)
            if self.buf_len() == 0 and self.buf_index != 0:
                self.buf = bytearray()
                self.buf_index = 0
            return m

Which equivalent to what is now in the MAVCesium server code: https://github.com/SamuelDudley/MAVCesium/blob/master/app/cesium_web_server.py#L215

Links to documentation are wrong

In the README, the link to the documentation does not load any page.

In the __init__ file, the link to the documentation leads to a page that has not been created yet.

fatal: memory overflow if length=0 with limited buffer size

In the C API v2.0, helper receive function mavlink_frame_char_buffer:
file: generator/C/include_v2.0/mavlink_helpers.h

In case of a glitchy packet with a len field value of 0 (or if you would have defined a message of length zero), and MAVLINK_MAX_PAYLOAD_LEN smaller than 249 (it is rounded to the next 8 bytes alignement, not sure if that's a good idea, so effectively 256 bytes):

The state machine doesn't handle correctly a null length:
In my case this happens because of a glitchy reception that changed the len field to zero (I don't have any zero-length messages) which happens every few minutes given my external conditions.

when it get to the state MAVLINK_PARSE_STATE_GOT_MSGID3 (line 714)
The code read the first byte even if len==0 and test status->packet_idx == rxmsg->len only after reading this first byte witch will be only true after reading 256 bytes instead of 0.

if you used MAVLINK_MAX_PAYLOAD_LEN to reduced the size of the buffer, their will be bytes overriding an unknown segment of memory witch leads to undefined behavior.

In my case using it on a atmega mcu it totally freezes the execution.

mavutil : Ignores target component/system when processing messages

mavutil won't work with multiple heartbeats/systems in a stream since it doesn't filter for the target system. It stores received messages regardless of the source. It processes system status, gps, and parameters regardless of source.

Possible code locations where a filter might be implemented.

in recv_mesg here:
https://github.com/ArduPilot/pymavlink/blob/master/mavutil.py#L320
and again here:
https://github.com/ArduPilot/pymavlink/blob/master/mavutil.py#L918

In post_message ;
https://github.com/ArduPilot/pymavlink/blob/master/mavutil.py#L224

The signature checking turns up a little late to the party and starts checking after the fact:
https://github.com/ArduPilot/pymavlink/blob/master/mavutil.py#L288

A simple fix is to check message source against self.target_system and self.target_component. If targets are zero then let the message through anyway. This will allow heartbeat to be set and seen.

Additional problem with wait_heartbeat and anything else using recv_match:
recv_match uses recv_msg. recv_msg does different things depending on the master type. One is to post_message, another is to store message directly etc..
The behaviour of recv_match changes depending on situation. For example: at startup you may wish to wait for any heartbeat or a specific heartbeat.

UPDATE: PR submitted here

Can you please put a ready to use Wireshark dissector lua script somewhere?

I've gone through python dependency hell and back now, tried all kinds of stuff, compiling from source, using pip packages, debian packages, tried starting all-over in a fresh vm, getting all kinds of strange error messages like File "/usr/src/mavlink/pymavlink/generator/mavgen.py", line 211, in <module> raise DeprecationWarning("Executable was moved to pymavlink.tools.mavgen") or File ./mavgen.py", line 18, in <module> from . import mavparse ValueError: Attempted relative import in non-package

Now after hours of tinkering I don't even get any output from mavgen.py or other commands like python -m pymavlink.generator.mavgen --lang=wlua mymavlink.xml -o mymavlink.lua anymore.

Apart from that, I'm totally confused by the documentation. Can you guys please, please put a ready-to-use wireshark dissector script somewhere? All I want to do is look at some wireshark traces with mavlink packets in them, not become a Python expert.

Mavutil / PX4: 'interpret_px4_mode' returns a mode not mapped in 'px4_map'

Hi guys,

I'm having this issue in mavutil.py:

'interpret_px4_mode' function is returning a not mapped mode in 'px4_map' (LAND) which actually exists based on this: https://docs.px4.io/en/flying/flight_mode_selection.html

Example:

# Heartbeat Message:
m = {'type' : 13, 'autopilot' : 12, 'base_mode' : 29, 'custom_mode' : 100925440, 'system_status' : 3, mavlink_version : 3}

mode = mavutil.interpret_px4_mode(base_mode, custom_mode)  # mode = 'LAND'
mode_is_valid = mode in mavutil.mode_mapping()  # False 'LAND' not in px4_map

I think the solution could be adding all the missing modes to px4_map.
Let me know how to proceed.

Java generator hard-codes sysid and compid

The Java code generator hard-codes a sysid of 255 and compid of 190, overwriting a user-specified sysid or compid. For example, this is the msg_heartbeat packing function:

public MAVLinkPacket pack(){
        MAVLinkPacket packet = new MAVLinkPacket(MAVLINK_MSG_LENGTH);
        packet.sysid = 255;
        packet.compid = 190;
        packet.msgid = MAVLINK_MSG_ID_HEARTBEAT;
              
        packet.payload.putUnsignedInt(custom_mode);
              
        packet.payload.putUnsignedByte(type);
              
        packet.payload.putUnsignedByte(autopilot);
              
        packet.payload.putUnsignedByte(base_mode);
              
        packet.payload.putUnsignedByte(system_status);
              
        packet.payload.putUnsignedByte(mavlink_version);
        
        return packet;
    }

This was most likely implemented because Java is typically used for a GCS, but that is not always the case. In my case, I am creating a mock drone in Java. It makes sense that these values could be used as defaults, but should not be hard-coded into packing functions.

My recommendation is to make these defaults in MAVLinkMessage, and remove them from the subclassed message packing functions.

Current version available on PyPI is confused

When I query for the current version of pymavlink on PyPI (using the site or pip), I get 2.0.6. However, when I install the package, I end up with 2.1.0.

Apparently 2.1.0 was uploaded on 2017-02-02, then 2.0.6 was uploaded on 2017-02-06. As a result, either PyPI is confused or pip is. This page shows that 2.0.6 is the latest version:

https://pypi.python.org/pypi/pymavlink

However, check this page to see the confusion:

https://pypi.python.org/pypi/pymavlink/2.1.0

That's the page for version 2.1.0, but it shows a "Latest version" of 2.0.6. Was 2.0.6 reuploaded on purpose, perhaps to deal with a regression? If so, 2.1.0 is what's actually being downloaded by my pip instance. I'm not sure why, other than it looking at the version numbers and trying to get the "highest" one. This is what I got:

root@docker:/# pip search pymavlink
pymavlink (2.0.6)  - Python MAVLink code

root@docker:/# pip install pymavlink
Collecting pymavlink
  Downloading pymavlink-2.1.0.tar.gz (2.8MB)
    100% |################################| 2.8MB 552kB/s

DFReader recv_msg() returns NANs

eg:
POS {TimeUS : 19429266, Lat : -22.2772117, Lng : -51.5002036, Alt : 0.0299999993294, RelHomeAlt : 0.0310829151422, RelOriginAlt : nan}

Fields with nan should possibly not be set, or set to None/False, or perhaps it indicates an internal dfreader/pymavlink bug that could be fixed?

PyMavlink on MacOS Sierra

Just edited setup.py to add specific MacOS info

if platform.system() == 'Darwin':
os.environ["ARCHFLAGS"] = "-arch i386 -arch x86_64"

and on pymavlink.py build I get this warning

creating build/temp.macosx-10.6-intel-2.7/mavnative
/usr/bin/clang -fno-strict-aliasing -fno-common -dynamic -g -DNDEBUG -g -fwrapv -O3 -Wall -Wstrict-prototypes -arch i386 -arch x86_64 -Igenerator/C/include_v1.0 -Igenerator/C/include_v2.0 -Imavnative -I/Library/Frameworks/Python.framework/Versions/2.7/include/python2.7 -c mavnative/mavnative.c -o build/temp.macosx-10.6-intel-2.7/mavnative/mavnative.o
mavnative/mavnative.c:155:13: warning: enumeration value
      'MAVLINK_PARSE_STATE_GOT_BAD_CRC1' not handled in switch [-Wswitch]
    switch (status->parse_state)
            ^
1 warning generated.
mavnative/mavnative.c:155:13: warning: enumeration value
      'MAVLINK_PARSE_STATE_GOT_BAD_CRC1' not handled in switch [-Wswitch]
    switch (status->parse_state)
            ^
1 warning generated.
/usr/bin/clang -bundle -undefined dynamic_lookup -g -arch i386 -arch x86_64 build/temp.macosx-10.6-intel-2.7/mavnative/mavnative.o -o build/lib.macosx-10.6-intel-2.7/mavnative.so
running build_scripts

I don't see it as a problem but just think it's ok to share.

Pointless API methods

Why does the generator populate the MAVLink class with (nominally) hundreds of methods to 'encode' and 'send' all the various message types? Those methods are just wrappers for instantiating message classes, and calling send(). Is there really some value in providing wrappers for these, at the cost of making the generated python file and generated documentation way longer than it needs to be?

Obviously, one million things probably use this API, but I just want to understand what the design intent was.

C implementation: hard fault on Cortex-M0 due to unaligned access to packed structure field

The mavlink_message_t structure is packed, and mavlink_finalize_message_chan and other functions take the address of checksum and other fields within the structure. This is illegal because those pointers may not have the required alignment for their type, and it results in hard-faults on Cortex-M0, which does not support unaligned loads.

I've worked around this on Cortex-M0 by removing the packing from the structure. There is no internal padding, so the only effect of packing is the alignment of the entire structure. However, mavlink_helpers.h hard-codes offsets into the structure, and assumes that the layout of the structure is the same as wire format in several places, which is also not guaranteed. The ideal fix would be to keep wire-format data in byte arrays, and native-format messages as un-packed structures, and convert between the two explicitly instead of by pointer cast.

Java mission messages throw exception

Several of the mission messages generated in Java throw IndexOutOfBoundsException when unpacked. So far I have seen this behavior with msg_mission_count, msg_mission_item, and msg_mission_ack.

For example, msg_mission_count.unpack():

public void unpack(MAVLinkPayload payload) {
        payload.resetIndex();
              
        this.count = payload.getUnsignedShort();
              
        this.target_system = payload.getUnsignedByte();
              
        this.target_component = payload.getUnsignedByte();
              
        this.mission_type = payload.getUnsignedByte();
    }

The final line throws the following exception (as recorded in Android adb):

11-22 16:32:23.321 10755-10882/io.diux.rogue.rosettadrone D/Rosetta: exception
                                                                     java.lang.IndexOutOfBoundsException: index=4 out of bounds (limit=4)
                                                                         at java.nio.Buffer.checkIndex(Buffer.java:528)
                                                                         at java.nio.HeapByteBuffer.get(HeapByteBuffer.java:118)
                                                                         at com.MAVLink.Messages.MAVLinkPayload.getUnsignedByte(MAVLinkPayload.java:62)
                                                                         at com.MAVLink.common.msg_mission_count.unpack(msg_mission_count.java:81)
                                                                         at com.MAVLink.common.msg_mission_count.<init>(msg_mission_count.java:100)
                                                                         at com.MAVLink.MAVLinkPacket.unpack(MAVLinkPacket.java:420)

mavfft_int.py: fix sample range selection for acc2 and acc3

Since the sample rates are not necessarily the same for all sensors, need to change the range specification from sample numbers to timestamps.
Also, since dropout-free ranges will not be the same for each sensor, it would be nice to label the ACC1 time domain plot with dropout ranges for all logged sensors. Currently you must select a range then look at the console printout to see whether there were any dropouts which affected each sensor.

C# generator problem

Generating C# source via mavlink generators gives the following errors:

This compiler is provided as part of the Microsoft (R) .NET Framework, but only supports language versions up to C# 5, which is no longer the latest version. For compilers that support newer versions of the C# programming language, see http://go.microsoft.com/fwlink/?LinkID=533240

error CS2001: Source file 'CS\common\ByteArrayUtil.cs' could not be found
error CS2001: Source file 'CS\common\FrameworkBitConverter.cs' could not be found
error CS2001: Source file 'CS\common\Mavlink.cs' could not be found
Error
Error: Compilation failed. (1)

This was reported in mavlink/mavlink:

status parse_error count reset on each mavlink_frame_char_buffer

I came across a strange thing in the C helper functions:
file: pymavlink/generator/C/include_v2.0/mavlink_helpers.h
line: 821

status->parse_error = 0;

seems strange to reset this counter, it become kind of useless.
It seems that either this line shouldn't exist, moreover, the parse_error value is never copied to r_mavlink_status so this should be added:

r_mavlink_status->parse_error = status->parse_error;

Or the parse_error counter is always zero even if there are actually errors

Bug in mavgen_wlua.py while trying to create a Mavlink Wireshark dissector(?)

I was trying to create a mavlink Wireshark dissector through mavgen (and consequently mavgen_wlua.py) and noticed that there is a problem in the lines 250-257 section, which are directly written to the LUA script.

      if (unknownFrameBeginOffset ~= 0) then  
            pinfo.cols.info:append("Unkown message22")  
            size = offset - unknownFrameBeginOffset  
            subtree:add(f.rawpayload, buffer(unknownFrameBeginOffset,size))  
            unknownFrameBeginOffset = 0  
            -- jump to next loop  
            break  
        end 

Essentially, LUA complains that unknownFrameBeginOffset was a variable that was not 'declared' in a global scope prior to this use, and throws an error saying attempt to perform arithmetic on a global nil value: unknownFrameBeginOffset. Once I set this variable to zero before the the message parsing and version checks (before line 205), it works as expected.

No module named 'mavexpression'

Hi, I followed this quickstart: http://python.dronekit.io/guide/quick_start.html
But when I type: python hello.py this is the result:

tarting copter simulator (SITL)
SITL already Downloaded and Extracted.
Ready to boot.
Traceback (most recent call last):
  File "hello.py", line 6, in <module>
    from dronekit import connect, VehicleMode
  File "/usr/lib/python3.5/site-packages/dronekit/__init__.py", line 42, in <module>
    from pymavlink import mavutil, mavwp
  File "/usr/lib/python3.5/site-packages/pymavlink/mavutil.py", line 10, in <module>
    import select, mavexpression
ImportError: No module named 'mavexpression'

I installed everything so I don't understand why.
I use Arch Linux, thanks

Failed Building wheel for lmxl error

Hey guys, Im a noob RPi user and an even bigger beginner at linux.
For some reason i can not get the pymavlink to install.
While connected to the RPi - according to
http://ardupilot.org/dev/docs/raspberry-pi-via-mavlink.html
everything works fine until the commands:

sudo pip install pymavlink
sudo pip install mavproxy

the scripts appears to be frozen on
Running setup.py bdist_wheel for lxml...
after too long of waiting i press ctrl+C and i get the errror

Failed building wheel for lxml.

this error did not happen when i had APsync (but had no com between pi and pixhawk) so im trying now on raspian.
any ideas?

Thanks!

Decode method behaviour.

What is the purpose of the method MAVLink.decode(...)? This code fails:

msg = mav.heartbeat_encode(0,0,0,0,0,0)
buf = msg.pack(may, force_mavlink1 = True)
msg2 = mav.decode(buf)

But succeeds if the last line is replaced with:

msg2 = mav.parse_char(c)

It appears the decode method fails to consider which MAVLink version the message contained in the buffer is?

Firstly, it seems totally unintuitive you can pass multiple characters at once to parse_char - the only clue in the documentation is that the method supposedly takes 'bytes' plural. Secondly, what then is the purpose of the decode method, if it isn't to decode a buffer of MAVLink bytes?

Problems parsing logs from APM 3.4.6: no gps data found

I'm trying to use some of the pymavlink utilities to parse this log file. Running mavsummarize.py results in:

Warning: No GPS data found, can't give position summary.

But running mavlogdump.py on the same file yields what appear to be GPS records, e.g:

2017-05-03 12:28:46.00: GPS {TimeUS : 80221069, Status : 3, GMS : 318541000, GWk : 1947, NSats : 15, HDop : 0.76, Lat : 42.3844842, Lng : -71.1628935, Alt : 16.77, Spd : 0.0608276240528, GCrs : 170.53767395, VZ : 0.00999999977648, U : 1}

And other utilities -- e.g., mavtogpx.py -- seem to have no problem finding position data in the log. Is there something wrong with the log? With the utilities?

Always False condition in mavlink_parse_char() in Parser.java

  public MAVLinkPacket mavlink_parse_char(int c) {
        msg_received = false;
        switch (state) {
            ...
            case MAVLINK_PARSE_STATE_GOT_STX:
                if (msg_received) {
                    msg_received = false;
                    state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
                }

Since msg_received is initialized to false just before the switch statement, the test of msg_received in the case statement will always be false, given the preceding cases always break out.

Want to send some custom message, but can not find enough example.

Hi,
I want to send a custom message to my device via USBtoTTL.
I have been searching some examples for long time, but still can not finish it.
Can you give me some help or one example?
Here is my code

from pymavlink.dialects.v10 import common as mavlink
from pymavlink import mavutil 

master = mavutil.mavlink_connection("/dev/ttyUSB0", 57600)
mav = master.mav
mav.command_long_send(target_system=71, target_component=67,
                      command=mavlink.MAV_CMD_DO_MOUNT_CONTROL,
                      confirmation=0,
                      param1=200,
                      param2=200,
                      param3=200,
                      param4=0,
                      param5=0,
                      param6=0,
                      param7=0)

and I got an output

Device /dev/ttyUSB0 is dead

I also tried other types of codes, but not work.
Any helpful reply will be appreciated, thank you very much.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.