#include <Python.h>
#include <structmember.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#include <setjmp.h>
#include "mavlink_defaults.h"
#include <mavlink_types.h>
#include <protocol.h>
Go to the source code of this file.
Classes | |
struct | NativeConnection |
struct | py_field_info_t |
struct | py_message_info_t |
struct | py_message_t |
Defines | |
#define | FALSE 0 |
#define | mavdebug(x...) |
#define | MAVLINK_ASSERT(x) assert(x) |
#define | MAVLINK_MESSAGE_CRC(msgid) py_message_info[msgid].crc_extra |
#define | MAVLINK_MESSAGE_LENGTH(msgid) py_message_info[msgid].len |
#define | MAVLINK_USE_CONVENIENCE_FUNCTIONS |
#define | MOD_RETURN(m) return |
#define | PyByteString_ConcatAndDel PyString_ConcatAndDel |
#define | PyByteString_FromString PyString_FromString |
#define | PyByteString_FromStringAndSize PyString_FromStringAndSize |
#define | PYTHON_ENTRY if(!setjmp(python_entry)) { |
#define | PYTHON_EXIT } else { return NULL; } |
#define | PYTHON_EXIT_INT } else { return -1; } |
#define | TRUE 1 |
Functions | |
void | __assert_fail (const char *__assertion, const char *__file, unsigned int __line, const char *__function) |
static void | comm_send_ch (mavlink_channel_t chan, uint8_t c) |
static PyObject * | createPyNone (void) |
static int | get_expectedlength (NativeConnection *self) |
static unsigned | get_field_size (int field_type) |
static int | get_py_typeinfo (char type_char, int array_size, unsigned *wire_offset) |
static void | init_message_info (PyObject *mavlink_map) |
PyMODINIT_FUNC | initmavnative (void) |
static PyObject * | msg_to_py (PyObject *msgclass, const py_message_t *pymsg) |
static void | NativeConnection_dealloc (NativeConnection *self) |
static PyObject * | NativeConnection_getexpectedlength (NativeConnection *self, void *closure) |
static int | NativeConnection_init (NativeConnection *self, PyObject *args, PyObject *kwds) |
static PyObject * | NativeConnection_new (PyTypeObject *type, PyObject *args, PyObject *kwds) |
MAVLINK_HELPER uint8_t | py_mavlink_parse_char (uint8_t c, py_message_t *pymsg, mavlink_status_t *status) |
static PyObject * | py_parse_buffer (NativeConnection *self, PyObject *args) |
static PyObject * | py_parse_chars (NativeConnection *self, PyObject *args) |
static PyObject * | pyextract_mavlink (const mavlink_message_t *msg, const py_field_info_t *field) |
static void | set_attribute (PyObject *obj, const char *attrName, PyObject *val) |
static void | set_pyerror (const char *msg) |
Variables | |
static uint8_t | info_inited = FALSE |
static mavlink_system_t | mavlink_system = {42,11,} |
static PyObject * | MAVNativeError |
static PyGetSetDef | NativeConnection_getseters [] |
static PyMemberDef | NativeConnection_members [] |
static PyMethodDef | NativeConnection_methods [] |
static PyTypeObject | NativeConnectionType |
static py_message_info_t | py_message_info [256] |
static jmp_buf | python_entry |
#define FALSE 0 |
Definition at line 69 of file mavnative.c.
#define mavdebug | ( | x... | ) |
Definition at line 116 of file mavnative.c.
#define MAVLINK_ASSERT | ( | x | ) | assert(x) |
Definition at line 47 of file mavnative.c.
#define MAVLINK_MESSAGE_CRC | ( | msgid | ) | py_message_info[msgid].crc_extra |
Definition at line 55 of file mavnative.c.
#define MAVLINK_MESSAGE_LENGTH | ( | msgid | ) | py_message_info[msgid].len |
Definition at line 64 of file mavnative.c.
Definition at line 35 of file mavnative.c.
#define MOD_RETURN | ( | m | ) | return |
Definition at line 937 of file mavnative.c.
#define PyByteString_ConcatAndDel PyString_ConcatAndDel |
Definition at line 30 of file mavnative.c.
#define PyByteString_FromString PyString_FromString |
Definition at line 28 of file mavnative.c.
#define PyByteString_FromStringAndSize PyString_FromStringAndSize |
Definition at line 29 of file mavnative.c.
#define PYTHON_ENTRY if(!setjmp(python_entry)) { |
Definition at line 125 of file mavnative.c.
#define PYTHON_EXIT } else { return NULL; } |
Definition at line 126 of file mavnative.c.
#define PYTHON_EXIT_INT } else { return -1; } |
Definition at line 127 of file mavnative.c.
#define TRUE 1 |
Definition at line 68 of file mavnative.c.
void __assert_fail | ( | const char * | __assertion, |
const char * | __file, | ||
unsigned int | __line, | ||
const char * | __function | ||
) |
Definition at line 322 of file mavnative.c.
static void comm_send_ch | ( | mavlink_channel_t | chan, |
uint8_t | c | ||
) | [static] |
Definition at line 42 of file mavnative.c.
static PyObject* createPyNone | ( | void | ) | [static] |
Definition at line 491 of file mavnative.c.
static int get_expectedlength | ( | NativeConnection * | self | ) | [static] |
How many bytes would we like to read to complete current packet
Definition at line 670 of file mavnative.c.
static unsigned get_field_size | ( | int | field_type | ) | [static] |
Definition at line 333 of file mavnative.c.
static int get_py_typeinfo | ( | char | type_char, |
int | array_size, | ||
unsigned * | wire_offset | ||
) | [static] |
Given a python type character & array_size advance the wire_offset to the correct next value.
Definition at line 386 of file mavnative.c.
static void init_message_info | ( | PyObject * | mavlink_map | ) | [static] |
We preconvert message info from the C style representation to python objects (to minimize # of object allocs).
FIXME - we really should free these PyObjects if our module gets unloaded.
mavlink_map | - the mavlink_map object from python a dict from an int msgid -> tuple(fmt, type_class, order_list, len_list, crc_extra) |
Definition at line 422 of file mavnative.c.
PyMODINIT_FUNC initmavnative | ( | void | ) |
Definition at line 944 of file mavnative.c.
static PyObject* msg_to_py | ( | PyObject * | msgclass, |
const py_message_t * | pymsg | ||
) | [static] |
Convert a message to a valid python representation.
FIXME - move msgclass, the mavstatus and channel context into an instance, created once with the mavfile object
Definition at line 611 of file mavnative.c.
static void NativeConnection_dealloc | ( | NativeConnection * | self | ) | [static] |
Definition at line 860 of file mavnative.c.
static PyObject* NativeConnection_getexpectedlength | ( | NativeConnection * | self, |
void * | closure | ||
) | [static] |
Definition at line 716 of file mavnative.c.
static int NativeConnection_init | ( | NativeConnection * | self, |
PyObject * | args, | ||
PyObject * | kwds | ||
) | [static] |
Definition at line 829 of file mavnative.c.
static PyObject* NativeConnection_new | ( | PyTypeObject * | type, |
PyObject * | args, | ||
PyObject * | kwds | ||
) | [static] |
Definition at line 819 of file mavnative.c.
MAVLINK_HELPER uint8_t py_mavlink_parse_char | ( | uint8_t | c, |
py_message_t * | pymsg, | ||
mavlink_status_t * | status | ||
) |
(originally from mavlink_helpers.h - but now customized to not be channel based) This is a convenience function which handles the complete MAVLink parsing. the function will parse one byte at a time and return the complete packet once it could be successfully decoded. Checksum and other failures will be silently ignored.
Messages are parsed into an internal buffer (one for each channel). When a complete message is received it is copies into *returnMsg and the channel's status is copied into *returnStats.
c | The char to parse |
returnMsg | NULL if no message could be decoded, the message data else |
returnStats | if a message was decoded, this is filled with the channel's stats |
Definition at line 147 of file mavnative.c.
static PyObject* py_parse_buffer | ( | NativeConnection * | self, |
PyObject * | args | ||
) | [static] |
Given an string of bytes.
This routine is more efficient than parse_chars, because it doesn't need to buffer characters.
Definition at line 779 of file mavnative.c.
static PyObject* py_parse_chars | ( | NativeConnection * | self, |
PyObject * | args | ||
) | [static] |
Given a byte array of bytes
Definition at line 726 of file mavnative.c.
static PyObject* pyextract_mavlink | ( | const mavlink_message_t * | msg, |
const py_field_info_t * | field | ||
) | [static] |
Extract a field value from a mavlink msg
Definition at line 515 of file mavnative.c.
static void set_attribute | ( | PyObject * | obj, |
const char * | attrName, | ||
PyObject * | val | ||
) | [static] |
Set an attribute, but handing over ownership on the value
Definition at line 502 of file mavnative.c.
static void set_pyerror | ( | const char * | msg | ) | [static] |
Definition at line 317 of file mavnative.c.
uint8_t info_inited = FALSE [static] |
Definition at line 91 of file mavnative.c.
mavlink_system_t mavlink_system = {42,11,} [static] |
Definition at line 41 of file mavnative.c.
PyObject* MAVNativeError [static] |
Definition at line 121 of file mavnative.c.
PyGetSetDef NativeConnection_getseters[] [static] |
{ {"expected_length", (getter)NativeConnection_getexpectedlength, NULL, "How many characters would the state-machine like to read now", NULL}, {NULL} }
Definition at line 870 of file mavnative.c.
PyMemberDef NativeConnection_members[] [static] |
{ {NULL} }
Definition at line 866 of file mavnative.c.
PyMethodDef NativeConnection_methods[] [static] |
{ {"parse_chars", (PyCFunction) py_parse_chars, METH_VARARGS, "Given a msg class and an array of bytes, Parse chars, returning a message or None"}, {"parse_buffer", (PyCFunction) py_parse_buffer, METH_VARARGS, "Given a msg class and a string like object, Parse chars, returning a (possibly empty) list of messages"}, {NULL, NULL}, }
Definition at line 878 of file mavnative.c.
PyTypeObject NativeConnectionType [static] |
Definition at line 887 of file mavnative.c.
py_message_info_t py_message_info[256] [static] |
Definition at line 90 of file mavnative.c.
jmp_buf python_entry [static] |
Definition at line 123 of file mavnative.c.