9 #include <structmember.h> 18 #if PY_MAJOR_VERSION >= 3 20 #define PyInt_AsLong PyLong_AsLong 21 #define PyInt_FromLong PyLong_FromLong 24 #define PyByteString_FromString PyBytes_FromString 25 #define PyByteString_FromStringAndSize PyBytes_FromStringAndSize 26 #define PyByteString_ConcatAndDel PyBytes_ConcatAndDel 28 #define PyByteString_FromString PyString_FromString 29 #define PyByteString_FromStringAndSize PyString_FromStringAndSize 30 #define PyByteString_ConcatAndDel PyString_ConcatAndDel 35 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS 37 #include <mavlink_types.h> 47 #define MAVLINK_ASSERT(x) assert(x) 55 #define MAVLINK_MESSAGE_CRC(msgid) py_message_info[msgid].crc_extra 64 #define MAVLINK_MESSAGE_LENGTH(msgid) py_message_info[msgid].len 113 #ifdef MAVNATIVE_DEBUG 114 # define mavdebug printf 116 # define mavdebug(x...) 125 #define PYTHON_ENTRY if(!setjmp(python_entry)) { 126 #define PYTHON_EXIT } else { return NULL; } // Used for routines thar return ptrs 127 #define PYTHON_EXIT_INT } else { return -1; } // Used for routines that return ints 217 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH 249 #if MAVLINK_CRC_EXTRA 253 if (c != (rxmsg->
checksum & 0xFF)) {
325 extern void __assert_fail(
const char *__assertion,
const char *__file,
unsigned int __line,
const char *__function)
329 sprintf(msg,
"Assertion failed: %s, %s:%d", __assertion, __file, __line);
375 mavdebug(
"BAD MAV TYPE %d\n", field_type);
411 int total_len =
get_field_size(type_code) * (array_size == 0 ? 1 : array_size);
413 *wire_offset += total_len;
428 PyObject *items_list = PyDict_Values(mavlink_map);
431 Py_ssize_t numMsgs = PyList_Size(items_list);
434 for(i = 0; i < numMsgs; i++) {
435 PyObject *type_class = PyList_GetItem(items_list, i);
438 PyObject *id_obj = PyObject_GetAttrString(type_class,
"id");
440 PyObject *name_obj = PyObject_GetAttrString(type_class,
"name");
442 PyObject *crc_extra_obj = PyObject_GetAttrString(type_class,
"crc_extra");
443 assert(crc_extra_obj);
444 PyObject *fieldname_list = PyObject_GetAttrString(type_class,
"ordered_fieldnames");
445 assert(fieldname_list);
448 PyObject *arrlen_list = PyObject_GetAttrString(type_class,
"array_lengths");
450 PyObject *type_format = PyObject_GetAttrString(type_class,
"native_format");
452 char *type_str = PyByteArray_AsString(type_format);
455 Py_ssize_t num_fields = PyList_Size(fieldname_list);
457 uint8_t
id = (uint8_t) PyInt_AsLong(id_obj);
463 d->
crc_extra = PyInt_AsLong(crc_extra_obj);
464 d->
fieldnames = PyObject_GetAttrString(type_class,
"fieldnames");
468 unsigned wire_offset = 0;
469 for(fnum = 0; fnum < num_fields; fnum++) {
470 PyObject *field_name_obj = PyList_GetItem(fieldname_list, fnum);
471 assert(field_name_obj);
472 Py_INCREF(field_name_obj);
474 PyObject *len_obj = PyList_GetItem(arrlen_list, fnum);
479 char type_char = type_str[1 + fnum];
483 d->
len = wire_offset;
485 Py_DECREF(crc_extra_obj);
486 Py_DECREF(arrlen_list);
487 Py_DECREF(type_format);
491 Py_DECREF(items_list);
505 static void set_attribute(PyObject *obj,
const char *attrName, PyObject *val) {
507 PyObject_SetAttrString(obj, attrName, val);
525 PyObject *result = NULL;
530 uint8_t string_ended =
FALSE;
532 if(arrayResult != NULL)
533 result = arrayResult;
536 for(index = 0; index < numValues; index++) {
537 PyObject *val = NULL;
539 switch(field->
type) {
544 if(stringResult && c == 0)
557 val = PyInt_FromLong(_MAV_RETURN_uint16_t(msg, offset));
560 val = PyInt_FromLong(_MAV_RETURN_int16_t(msg, offset));
563 val = PyLong_FromLong(_MAV_RETURN_uint32_t(msg, offset));
566 val = PyInt_FromLong(_MAV_RETURN_int32_t(msg, offset));
569 val = PyLong_FromLongLong(_MAV_RETURN_uint64_t(msg, offset));
572 val = PyLong_FromLongLong(_MAV_RETURN_int64_t(msg, offset));
575 val = PyFloat_FromDouble(_MAV_RETURN_float(msg, offset));
578 val = PyFloat_FromDouble(_MAV_RETURN_double(msg, offset));
588 if(arrayResult != NULL)
589 PyList_SetItem(arrayResult, index, val);
590 else if(stringResult != NULL) {
596 result = stringResult;
618 mavdebug(
"Found a msg: %s\n", PyString_AS_STRING(info->
name));
622 PyObject *argList = PyTuple_Pack(2, info->
id, info->
name);
623 PyObject *obj = PyObject_CallObject(msgclass, argList);
624 uint8_t objValid =
TRUE;
629 PyObject *header = PyObject_GetAttrString(obj,
"_header");
644 PyObject_SetAttrString(obj,
"_fieldnames", info->
fieldnames);
649 for(fnum = 0; fnum < info->
num_fields && objValid; fnum++) {
654 PyObject_SetAttr(obj, f->
name, val);
679 switch(self->mav_status.parse_state) {
688 desired = msg->
len + 6;
691 desired = msg->
len + 5;
694 desired = msg->
len + 4;
697 desired = msg->
len + 3;
700 desired = msg->
len -
self->mav_status.packet_idx + 2;
714 mavdebug(
"in state %d, expected_length=%d\n", (
int) self->mav_status.parse_state, desired);
734 if (!PyArg_ParseTuple(args,
"O", &byteObj)) {
739 assert(PyByteArray_Check(byteObj));
740 Py_ssize_t numBytes = PyByteArray_Size(byteObj);
741 mavdebug(
"numbytes %u\n", (
unsigned) numBytes);
743 char *start = PyByteArray_AsString(byteObj);
746 PyObject *result = NULL;
756 result =
msg_to_py(self->MAVLinkMessage, &self->msg);
763 memmove(start, bytes, numBytes);
764 PyByteArray_Resize(byteObj, numBytes);
786 mavdebug(
"Enter py_parse_buffer\n");
789 Py_ssize_t numBytes = 0;
791 if (!PyArg_ParseTuple(args,
"s#", &bytes, &numBytes)) {
798 PyObject* list = PyList_New(0);
806 PyObject *obj =
msg_to_py(self->MAVLinkMessage, &self->msg);
808 PyList_Append(list, obj);
827 return (PyObject *)
self;
838 memset(&self->mav_status, 0,
sizeof(self->mav_status));
840 PyObject* msgclass, *mavlink_map;
841 if (!PyArg_ParseTuple(args,
"OO", &msgclass, &mavlink_map)) {
848 self->MAVLinkMessage = msgclass;
865 Py_XDECREF(self->MAVLinkMessage);
866 Py_TYPE(
self)->tp_free((PyObject*)
self);
876 "How many characters would the state-machine like to read now",
883 "Given a msg class and an array of bytes, Parse chars, returning a message or None"},
885 "Given a msg class and a string like object, Parse chars, returning a (possibly empty) list of messages"},
891 #if PY_MAJOR_VERSION >= 3 892 PyVarObject_HEAD_INIT(NULL, 0)
894 PyObject_HEAD_INIT(NULL)
897 "mavnative.NativeConnection",
917 "NativeConnection objects",
937 #if PY_MAJOR_VERSION >= 3 938 #define MOD_RETURN(m) return m 940 #define MOD_RETURN(m) return 944 #if PY_MAJOR_VERSION >= 3 945 PyInit_mavnative(
void)
953 #if PY_MAJOR_VERSION < 3 954 static PyMethodDef ModuleMethods[] = {
955 {NULL, NULL, 0, NULL}
958 PyObject *
m = Py_InitModule3(
"mavnative", ModuleMethods,
"Mavnative module");
962 static PyModuleDef mod_def = {
963 PyModuleDef_HEAD_INIT,
967 NULL, NULL, NULL, NULL, NULL
970 PyObject *m = PyModule_Create(&mod_def);
973 MAVNativeError = PyErr_NewException(
"mavnative.error", NULL, NULL);
uint8_t magic
sent at end of packet
static PyObject * NativeConnection_getexpectedlength(NativeConnection *self, void *closure)
static PyObject * py_parse_chars(NativeConnection *self, PyObject *args)
static void set_pyerror(const char *msg)
static PyObject * py_parse_buffer(NativeConnection *self, PyObject *args)
static PyObject * NativeConnection_new(PyTypeObject *type, PyObject *args, PyObject *kwds)
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t *msg)
#define MAVLINK_MESSAGE_LENGTH(msgid)
mavlink_message_type_t type
#define _MAV_RETURN_uint8_t(msg, wire_offset)
uint8_t msgid
ID of message in payload.
static void init_message_info(PyObject *mavlink_map)
#define MAVLINK_MAX_PACKET_LEN
Maximum packet length.
MAVLINK_HELPER uint8_t py_mavlink_parse_char(uint8_t c, py_message_t *pymsg, mavlink_status_t *status)
static PyObject * msg_to_py(PyObject *msgclass, const py_message_t *pymsg)
static py_message_info_t py_message_info[256]
#define MAVLINK_MESSAGE_CRC(msgid)
uint8_t seq
Sequence of packet.
#define PyByteString_ConcatAndDel
static PyObject * pyextract_mavlink(const mavlink_message_t *msg, const py_field_info_t *field)
static PyObject * createPyNone(void)
#define MAVLINK_MAX_FIELDS
static void set_attribute(PyObject *obj, const char *attrName, PyObject *val)
static int get_py_typeinfo(char type_char, int array_size, unsigned *wire_offset)
static void NativeConnection_dealloc(NativeConnection *self)
static int NativeConnection_init(NativeConnection *self, PyObject *args, PyObject *kwds)
uint8_t msg_received
Number of received messages.
mavlink_parse_state_t parse_state
Parsing state machine.
static jmp_buf python_entry
#define _MAV_RETURN_int8_t(msg, wire_offset)
#define _MAV_RETURN_char(msg, wire_offset)
static unsigned get_field_size(int field_type)
#define _MAV_PAYLOAD_NON_CONST(msg)
uint8_t parse_error
Number of parse errors.
#define MAVLINK_MAX_PAYLOAD_LEN
Maximum payload length.
uint16_t packet_rx_drop_count
Number of packet drops.
uint8_t bytes[MAVLINK_MAX_PACKET_LEN]
static mavlink_system_t mavlink_system
void __assert_fail(const char *__assertion, const char *__file, unsigned int __line, const char *__function)
static PyGetSetDef NativeConnection_getseters[]
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t *msg, uint8_t c)
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
uint16_t packet_rx_success_count
Received packets.
static PyMemberDef NativeConnection_members[]
mavlink_status_t mav_status
uint8_t sysid
ID of message sender system/aircraft.
uint8_t compid
ID of the message sender component.
uint8_t packet_idx
Index in current packet.
static PyObject * MAVNativeError
uint8_t len
Length of payload.
uint8_t current_rx_seq
Sequence number of last packet received.
py_field_info_t fields[MAVLINK_MAX_FIELDS]
unsigned int array_length
uint8_t buffer_overrun
Number of buffer overruns.
static uint8_t info_inited
PyObject_HEAD PyObject * MAVLinkMessage
#define PyByteString_FromStringAndSize
static PyTypeObject NativeConnectionType
static PyMethodDef NativeConnection_methods[]
static int get_expectedlength(NativeConnection *self)
#define PyByteString_FromString
PyMODINIT_FUNC initmavnative(void)