#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.
|
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) |
|
#define MAVLINK_ASSERT |
( |
|
x | ) |
assert(x) |
#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_EXIT } else { return NULL; } |
#define PYTHON_EXIT_INT } else { return -1; } |
void __assert_fail |
( |
const char * |
__assertion, |
|
|
const char * |
__file, |
|
|
unsigned int |
__line, |
|
|
const char * |
__function |
|
) |
| |
static PyObject* createPyNone |
( |
void |
| ) |
|
|
static |
How many bytes would we like to read to complete current packet
Definition at line 673 of file mavnative.c.
static unsigned get_field_size |
( |
int |
field_type | ) |
|
|
static |
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.
- Returns
- the equivalent C++ type code.
Definition at line 389 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.
- Parameters
-
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 425 of file mavnative.c.
PyMODINIT_FUNC initmavnative |
( |
void |
| ) |
|
static PyObject* msg_to_py |
( |
PyObject * |
msgclass, |
|
|
const py_message_t * |
pymsg |
|
) |
| |
|
static |
Convert a message to a valid python representation.
- Returns
- new message, or null if a valid encoding could not be made
FIXME - move msgclass, the mavstatus and channel context into an instance, created once with the mavfile object
Definition at line 614 of file mavnative.c.
static PyObject* NativeConnection_getexpectedlength |
( |
NativeConnection * |
self, |
|
|
void * |
closure |
|
) |
| |
|
static |
static int NativeConnection_init |
( |
NativeConnection * |
self, |
|
|
PyObject * |
args, |
|
|
PyObject * |
kwds |
|
) |
| |
|
static |
static PyObject* NativeConnection_new |
( |
PyTypeObject * |
type, |
|
|
PyObject * |
args, |
|
|
PyObject * |
kwds |
|
) |
| |
|
static |
(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.
- Parameters
-
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 |
- Returns
- 0 if no message could be decoded, 1 else
Definition at line 147 of file mavnative.c.
Given an string of bytes.
This routine is more efficient than parse_chars, because it doesn't need to buffer characters.
- Returns
- a list of MAVProxy_message objects
Definition at line 782 of file mavnative.c.
Given a byte array of bytes
- Returns
- a list of MAVProxy_message objects
Definition at line 729 of file mavnative.c.
Extract a field value from a mavlink msg
- Returns
- possibly null if mavlink stream is corrupted (FIXME, caller should check)
Definition at line 518 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 505 of file mavnative.c.
static void set_pyerror |
( |
const char * |
msg | ) |
|
|
static |
uint8_t info_inited = FALSE |
|
static |
PyGetSetDef NativeConnection_getseters[] |
|
static |
Initial value:= {
{"expected_length",
"How many characters would the state-machine like to read now",
NULL},
{NULL}
}
static PyObject * NativeConnection_getexpectedlength(NativeConnection *self, void *closure)
Definition at line 873 of file mavnative.c.
PyMemberDef NativeConnection_members[] |
|
static |
PyMethodDef NativeConnection_methods[] |
|
static |
Initial value:= {
"Given a msg class and an array of bytes, Parse chars, returning a message or None"},
"Given a msg class and a string like object, Parse chars, returning a (possibly empty) list of messages"},
{NULL, NULL},
}
static PyObject * py_parse_chars(NativeConnection *self, PyObject *args)
static PyObject * py_parse_buffer(NativeConnection *self, PyObject *args)
Definition at line 881 of file mavnative.c.
PyTypeObject NativeConnectionType |
|
static |