mavnative.c
Go to the documentation of this file.
1 /*
2  Native mavlink glue for python.
3  Author: kevinh@geeksville.com
4 */
5 
6 #undef NDEBUG
7 
8 #include <Python.h>
9 #include <structmember.h>
10 
11 #include <stdio.h>
12 #include <stdlib.h>
13 #include <stdint.h>
14 #include <assert.h>
15 #include <stddef.h>
16 #include <setjmp.h>
17 
18 #if PY_MAJOR_VERSION >= 3
19 // In python3 it only has longs, not 32 bit ints
20 #define PyInt_AsLong PyLong_AsLong
21 #define PyInt_FromLong PyLong_FromLong
22 
23 // We returns strings for byte arreays in python2, but bytes objects in python3
24 #define PyByteString_FromString PyBytes_FromString
25 #define PyByteString_FromStringAndSize PyBytes_FromStringAndSize
26 #define PyByteString_ConcatAndDel PyBytes_ConcatAndDel
27 #else
28 #define PyByteString_FromString PyString_FromString
29 #define PyByteString_FromStringAndSize PyString_FromStringAndSize
30 #define PyByteString_ConcatAndDel PyString_ConcatAndDel
31 #endif
32 
33 #include "mavlink_defaults.h"
34 
35 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
36 
37 #include <mavlink_types.h>
38 
39 // Mavlink send support
40 // Not currently used, but keeps mavlink_helpers send code happy
41 static mavlink_system_t mavlink_system = {42,11,};
42 static void comm_send_ch(mavlink_channel_t chan, uint8_t c) {
43  // Sending not supported yet in native code
44  assert(0);
45 }
46 
47 #define MAVLINK_ASSERT(x) assert(x)
48 
49 // static mavlink_message_t last_msg;
50 
51 /*
52  default message crc function. You can override this per-system to
53  put this data in a different memory segment
54 */
55 #define MAVLINK_MESSAGE_CRC(msgid) py_message_info[msgid].crc_extra
56 
57 /* Enable this option to check the length of each message.
58  This allows invalid messages to be caught much sooner. Use if the transmission
59  medium is prone to missing (or extra) characters (e.g. a radio that fades in
60  and out). Only use if the channel will only contain messages types listed in
61  the headers.
62 */
63 
64 #define MAVLINK_MESSAGE_LENGTH(msgid) py_message_info[msgid].len
65 
66 // #include <mavlink.h>
67 
68 #define TRUE 1
69 #define FALSE 0
70 
71 typedef struct {
72  PyObject *name; // name of this field
73  mavlink_message_type_t type; // type of this field
74  unsigned int array_length; // if non-zero, field is an array
75  unsigned int wire_offset; // offset of each field in the payload
77 
78 // note that in this structure the order of fields is the order
79 // in the XML file, not necessary the wire order
80 typedef struct {
81  PyObject *id; // The int id for this msg
82  PyObject *name; // name of the message
83  unsigned len; // the raw message length of this message - not including headers & CRC
84  uint8_t crc_extra; // the CRC extra for this message
85  unsigned num_fields; // how many fields in this message
86  PyObject *fieldnames; // fieldnames in the correct order expected by user (not wire order)
87  py_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
89 
91 static uint8_t info_inited = FALSE; // We only do the init once (assuming only one dialect in use)
92 
93 #include <protocol.h>
94 
98 typedef struct {
100  int numBytes;
101  uint8_t bytes[MAVLINK_MAX_PACKET_LEN];
102 } py_message_t;
103 
104 typedef struct {
105  PyObject_HEAD
106 
107  PyObject *MAVLinkMessage;
111 
112 // #define MAVNATIVE_DEBUG
113 #ifdef MAVNATIVE_DEBUG
114 # define mavdebug printf
115 #else
116 # define mavdebug(x...)
117 #endif
118 
119 
120 // My exception type
121 static PyObject *MAVNativeError;
122 
123 static jmp_buf python_entry;
124 
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
128 
129 
148 {
149  mavlink_message_t *rxmsg = &pymsg->msg;
150 
151  int bufferIndex = 0;
152 
153  status->msg_received = 0;
154 
155  switch (status->parse_state)
156  {
159  if (c == MAVLINK_STX)
160  {
162  rxmsg->len = 0;
163  pymsg->numBytes = 0;
164  rxmsg->magic = c;
165  mavlink_start_checksum(rxmsg);
166  pymsg->bytes[pymsg->numBytes++] = c;
167  }
168  break;
169 
171  if (status->msg_received
172 /* Support shorter buffers than the
173  default maximum packet size */
174 #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
176 #endif
177  )
178  {
179  status->buffer_overrun++;
180  status->parse_error++;
181  status->msg_received = 0;
183  }
184  else
185  {
186  // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
187  rxmsg->len = c;
188  status->packet_idx = 0;
189  mavlink_update_checksum(rxmsg, c);
190  pymsg->bytes[pymsg->numBytes++] = c;
192  }
193  break;
194 
196  rxmsg->seq = c;
197  mavlink_update_checksum(rxmsg, c);
198  pymsg->bytes[pymsg->numBytes++] = c;
200  break;
201 
203  rxmsg->sysid = c;
204  mavlink_update_checksum(rxmsg, c);
205  pymsg->bytes[pymsg->numBytes++] = c;
207  break;
208 
210  rxmsg->compid = c;
211  mavlink_update_checksum(rxmsg, c);
212  pymsg->bytes[pymsg->numBytes++] = c;
214  break;
215 
217 #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
218  if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
219  {
220  status->parse_error++;
222  break;
223  }
224 #endif
225  rxmsg->msgid = c;
226  mavlink_update_checksum(rxmsg, c);
227  pymsg->bytes[pymsg->numBytes++] = c;
228  if (rxmsg->len == 0)
229  {
231  }
232  else
233  {
235  }
236  break;
237 
239  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
240  mavlink_update_checksum(rxmsg, c);
241  pymsg->bytes[pymsg->numBytes++] = c;
242  if (status->packet_idx == rxmsg->len)
243  {
245  }
246  break;
247 
249 #if MAVLINK_CRC_EXTRA
251 #endif
252  pymsg->bytes[pymsg->numBytes++] = c;
253  if (c != (rxmsg->checksum & 0xFF)) {
254  // Check first checksum byte
255  status->parse_error++;
256  status->msg_received = 0;
258  if (c == MAVLINK_STX)
259  {
261  rxmsg->len = 0;
262  mavlink_start_checksum(rxmsg);
263  }
264  }
265  else
266  {
268  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
269  }
270  break;
271 
273  pymsg->bytes[pymsg->numBytes++] = c;
274  if (c != (rxmsg->checksum >> 8)) {
275  // Check second checksum byte
276  status->parse_error++;
277  status->msg_received = 0;
279  if (c == MAVLINK_STX)
280  {
282  rxmsg->len = 0;
283  mavlink_start_checksum(rxmsg);
284  }
285  }
286  else
287  {
288  // Successfully got message
289  status->msg_received = 1;
291  _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
292  }
293  break;
294 
295  case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: // not used, just to fix compiler warning
296  break;
297  }
298 
299  bufferIndex++;
300  // If a message has been sucessfully decoded, check index
301  if (status->msg_received == 1)
302  {
303  //while(status->current_seq != rxmsg->seq)
304  //{
305  // status->packet_rx_drop_count++;
306  // status->current_seq++;
307  //}
308  status->current_rx_seq = rxmsg->seq;
309  // Initial condition: If no packet has been received so far, drop count is undefined
310  if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
311  // Count this packet as received
312  status->packet_rx_success_count++;
313  }
314 
315  return status->msg_received;
316 }
317 
318 
319 // Raise a python exception
320 static void set_pyerror(const char *msg) {
321  PyErr_SetString(MAVNativeError, msg);
322 }
323 
324 // Pass assertion failures back to python (if we can)
325 extern void __assert_fail(const char *__assertion, const char *__file, unsigned int __line, const char *__function)
326 {
327  char msg[256];
328 
329  sprintf(msg, "Assertion failed: %s, %s:%d", __assertion, __file, __line);
330 
331  set_pyerror(msg);
332  longjmp(python_entry, 1);
333 }
334 
335 
336 static unsigned get_field_size(int field_type) {
337  unsigned fieldSize;
338 
339  switch(field_type)
340  {
341  case MAVLINK_TYPE_CHAR:
342  fieldSize = 1;
343  break;
345  fieldSize = 1;
346  break;
347  case MAVLINK_TYPE_INT8_T:
348  fieldSize = 1;
349  break;
351  fieldSize = 2;
352  break;
354  fieldSize = 2;
355  break;
357  fieldSize = 4;
358  break;
360  fieldSize = 4;
361  break;
363  fieldSize = 8;
364  break;
365  case MAVLINK_TYPE_INT64_T:
366  fieldSize = 8;
367  break;
368  case MAVLINK_TYPE_FLOAT:
369  fieldSize = 4;
370  break;
371  case MAVLINK_TYPE_DOUBLE:
372  fieldSize = 8;
373  break;
374  default:
375  mavdebug("BAD MAV TYPE %d\n", field_type);
376  set_pyerror("Unexpected mavlink type");
377  fieldSize = 1;
378  }
379 
380  return fieldSize;
381 }
382 
383 
389 static int get_py_typeinfo(char type_char, int array_size, unsigned *wire_offset)
390 {
391  int type_code;
392 
393  switch(type_char)
394  {
395  case 'f': type_code = MAVLINK_TYPE_FLOAT; break;
396  case 'd': type_code = MAVLINK_TYPE_DOUBLE; break;
397  case 'c': type_code = MAVLINK_TYPE_CHAR; break;
398  case 'v': type_code = MAVLINK_TYPE_UINT8_T; break;
399  case 'b': type_code = MAVLINK_TYPE_INT8_T; break;
400  case 'B': type_code = MAVLINK_TYPE_UINT8_T; break;
401  case 'h': type_code = MAVLINK_TYPE_INT16_T; break;
402  case 'H': type_code = MAVLINK_TYPE_UINT16_T; break;
403  case 'i': type_code = MAVLINK_TYPE_INT32_T; break;
404  case 'I': type_code = MAVLINK_TYPE_UINT32_T; break;
405  case 'q': type_code = MAVLINK_TYPE_INT64_T; break;
406  case 'Q': type_code = MAVLINK_TYPE_UINT64_T; break;
407  default:
408  assert(0);
409  }
410 
411  int total_len = get_field_size(type_code) * (array_size == 0 ? 1 : array_size);
412 
413  *wire_offset += total_len;
414 
415  return type_code;
416 }
417 
425 static void init_message_info(PyObject *mavlink_map) {
426  // static const mavlink_message_info_t src[256] = MAVLINK_MESSAGE_INFO;
427 
428  PyObject *items_list = PyDict_Values(mavlink_map);
429  assert(items_list); // A list of the tuples in mavlink_map
430 
431  Py_ssize_t numMsgs = PyList_Size(items_list);
432 
433  int i;
434  for(i = 0; i < numMsgs; i++) {
435  PyObject *type_class = PyList_GetItem(items_list, i); // returns a _borrowed_ reference
436  assert(type_class);
437 
438  PyObject *id_obj = PyObject_GetAttrString(type_class, "id"); // A _new_ reference
439  assert(id_obj);
440  PyObject *name_obj = PyObject_GetAttrString(type_class, "name"); // A new reference
441  assert(name_obj);
442  PyObject *crc_extra_obj = PyObject_GetAttrString(type_class, "crc_extra"); // A new reference
443  assert(crc_extra_obj);
444  PyObject *fieldname_list = PyObject_GetAttrString(type_class, "ordered_fieldnames"); // A new reference
445  assert(fieldname_list);
446  //PyObject *order_list = PyObject_GetAttrString(type_class, "orders"); // A new reference
447  //assert(order_list);
448  PyObject *arrlen_list = PyObject_GetAttrString(type_class, "array_lengths"); // A new reference
449  assert(arrlen_list);
450  PyObject *type_format = PyObject_GetAttrString(type_class, "native_format"); // A new reference
451  assert(type_format);
452  char *type_str = PyByteArray_AsString(type_format);
453  assert(type_str);
454 
455  Py_ssize_t num_fields = PyList_Size(fieldname_list);
456 
457  uint8_t id = (uint8_t) PyInt_AsLong(id_obj);
458  py_message_info_t *d = &py_message_info[id];
459 
460  d->id = id_obj;
461  d->name = name_obj;
462  d->num_fields = num_fields;
463  d->crc_extra = PyInt_AsLong(crc_extra_obj);
464  d->fieldnames = PyObject_GetAttrString(type_class, "fieldnames"); // A new reference
465  assert(d->fieldnames);
466 
467  int fnum;
468  unsigned wire_offset = 0;
469  for(fnum = 0; fnum < num_fields; fnum++) {
470  PyObject *field_name_obj = PyList_GetItem(fieldname_list, fnum); // returns a _borrowed_ reference
471  assert(field_name_obj);
472  Py_INCREF(field_name_obj);
473 
474  PyObject *len_obj = PyList_GetItem(arrlen_list, fnum); // returns a _borrowed_ reference
475  assert(len_obj);
476 
477  d->fields[fnum].name = field_name_obj;
478  d->fields[fnum].array_length = PyInt_AsLong(len_obj);
479  char type_char = type_str[1 + fnum];
480  d->fields[fnum].wire_offset = wire_offset; // Store the current offset before advancing
481  d->fields[fnum].type = get_py_typeinfo(type_char, d->fields[fnum].array_length, &wire_offset);
482  }
483  d->len = wire_offset;
484 
485  Py_DECREF(crc_extra_obj);
486  Py_DECREF(arrlen_list);
487  Py_DECREF(type_format);
488  //Py_DECREF(order_list);
489  }
490 
491  Py_DECREF(items_list);
492 }
493 
494 static PyObject *createPyNone(void)
495 {
496  Py_INCREF(Py_None);
497  return Py_None;
498 }
499 
500 
501 
505 static void set_attribute(PyObject *obj, const char *attrName, PyObject *val) {
506  assert(val);
507  PyObject_SetAttrString(obj, attrName, val);
508  Py_DECREF(val);
509 }
510 
511 
512 
518 static PyObject *pyextract_mavlink(const mavlink_message_t *msg, const py_field_info_t *field) {
519  unsigned offset = field->wire_offset;
520  int index;
521 
522  // For arrays of chars we build the result in a string instead of an array
523  PyObject *arrayResult = (field->array_length != 0 && field->type != MAVLINK_TYPE_CHAR) ? PyList_New(field->array_length) : NULL;
524  PyObject *stringResult = (field->array_length != 0 && field->type == MAVLINK_TYPE_CHAR) ? PyByteString_FromString("") : NULL;
525  PyObject *result = NULL;
526 
527  int numValues = (field->array_length == 0) ? 1 : field->array_length;
528  unsigned fieldSize = get_field_size(field->type);
529 
530  uint8_t string_ended = FALSE;
531 
532  if(arrayResult != NULL)
533  result = arrayResult;
534 
535  // Either build a full array of results, or return a single value
536  for(index = 0; index < numValues; index++) {
537  PyObject *val = NULL;
538 
539  switch(field->type) {
540  case MAVLINK_TYPE_CHAR: {
541  // If we are building a string, stop writing when we see a null char
542  char c = _MAV_RETURN_char(msg, offset);
543 
544  if(stringResult && c == 0)
545  string_ended = TRUE;
546 
547  val = PyByteString_FromStringAndSize(&c, 1);
548  break;
549  }
551  val = PyInt_FromLong(_MAV_RETURN_uint8_t(msg, offset));
552  break;
553  case MAVLINK_TYPE_INT8_T:
554  val = PyInt_FromLong(_MAV_RETURN_int8_t(msg, offset));
555  break;
557  val = PyInt_FromLong(_MAV_RETURN_uint16_t(msg, offset));
558  break;
560  val = PyInt_FromLong(_MAV_RETURN_int16_t(msg, offset));
561  break;
563  val = PyLong_FromLong(_MAV_RETURN_uint32_t(msg, offset));
564  break;
566  val = PyInt_FromLong(_MAV_RETURN_int32_t(msg, offset));
567  break;
569  val = PyLong_FromLongLong(_MAV_RETURN_uint64_t(msg, offset));
570  break;
572  val = PyLong_FromLongLong(_MAV_RETURN_int64_t(msg, offset));
573  break;
574  case MAVLINK_TYPE_FLOAT:
575  val = PyFloat_FromDouble(_MAV_RETURN_float(msg, offset));
576  break;
577  case MAVLINK_TYPE_DOUBLE:
578  val = PyFloat_FromDouble(_MAV_RETURN_double(msg, offset));
579  break;
580  default:
581  mavdebug("BAD MAV TYPE %d\n", field->type);
582  set_pyerror("Unexpected mavlink type");
583  return NULL;
584  }
585  offset += fieldSize;
586 
587  assert(val);
588  if(arrayResult != NULL)
589  PyList_SetItem(arrayResult, index, val);
590  else if(stringResult != NULL) {
591  if(!string_ended)
592  PyByteString_ConcatAndDel(&stringResult, val);
593  else
594  Py_DECREF(val); // We didn't use this char
595 
596  result = stringResult;
597  }
598  else // Not building an array
599  result = val;
600  }
601 
602  assert(result);
603  return result;
604 }
605 
606 
614 static PyObject *msg_to_py(PyObject* msgclass, const py_message_t *pymsg) {
615  const mavlink_message_t *msg = &pymsg->msg;
616  const py_message_info_t *info = &py_message_info[msg->msgid];
617 
618  mavdebug("Found a msg: %s\n", PyString_AS_STRING(info->name));
619 
620  /* Call the class object to create our instance */
621  // PyObject *obj = PyObject_CallObject((PyObject *) &NativeConnectionType, null);
622  PyObject *argList = PyTuple_Pack(2, info->id, info->name);
623  PyObject *obj = PyObject_CallObject(msgclass, argList);
624  uint8_t objValid = TRUE;
625  assert(obj);
626  Py_DECREF(argList);
627 
628  // Find the header subobject
629  PyObject *header = PyObject_GetAttrString(obj, "_header");
630  assert(header);
631 
632  // msgid already set in the constructor call
633  set_attribute(header, "mlen", PyInt_FromLong(msg->len));
634  set_attribute(header, "seq", PyInt_FromLong(msg->seq));
635  set_attribute(header, "srcSystem", PyInt_FromLong(msg->sysid));
636  set_attribute(header, "srcComponent", PyInt_FromLong(msg->compid));
637  Py_DECREF(header);
638  header = NULL;
639 
640  // FIXME - we should generate this expensive field only as needed (via a getattr override)
641  set_attribute(obj, "_msgbuf", PyByteArray_FromStringAndSize((const char *) pymsg->bytes, pymsg->numBytes));
642 
643  // Now add all the fields - FIXME - do this lazily using getattr overrides
644  PyObject_SetAttrString(obj, "_fieldnames", info->fieldnames); // Will increment the reference count
645 
646  // FIXME - reuse the fieldnames list from python - so it is in the right order
647 
648  int fnum;
649  for(fnum = 0; fnum < info->num_fields && objValid; fnum++) {
650  const py_field_info_t *f = &info->fields[fnum];
651  PyObject *val = pyextract_mavlink(msg, f);
652 
653  if(val != NULL) {
654  PyObject_SetAttr(obj, f->name, val);
655  Py_DECREF(val); // We no longer need val, the attribute will keep a ref
656  }
657  else
658  objValid = FALSE;
659  }
660 
661  if(objValid)
662  return obj;
663  else {
664  Py_DECREF(obj);
665  return NULL;
666  }
667 }
668 
669 
674 {
675  int desired;
676 
677  mavlink_message_t *msg = &self->msg.msg;
678 
679  switch(self->mav_status.parse_state) {
682  desired = 8;
683  break;
685  desired = 7;
686  break;
688  desired = msg->len + 6;
689  break;
691  desired = msg->len + 5;
692  break;
694  desired = msg->len + 4;
695  break;
697  desired = msg->len + 3;
698  break;
700  desired = msg->len - self->mav_status.packet_idx + 2;
701  break;
703  desired = 2;
704  break;
706  desired = 1;
707  break;
708  default:
709  // Huh? Just claim 1
710  desired = 1;
711  break;
712  }
713 
714  mavdebug("in state %d, expected_length=%d\n", (int) self->mav_status.parse_state, desired);
715  return desired;
716 }
717 
718 
719 static PyObject *NativeConnection_getexpectedlength(NativeConnection *self, void *closure)
720 {
721  return PyInt_FromLong(get_expectedlength(self));
722 }
723 
728 static PyObject *
730 {
732 
733  PyObject* byteObj;
734  if (!PyArg_ParseTuple(args, "O", &byteObj)) {
735  set_pyerror("Invalid arguments");
736  return NULL;
737  }
738 
739  assert(PyByteArray_Check(byteObj));
740  Py_ssize_t numBytes = PyByteArray_Size(byteObj);
741  mavdebug("numbytes %u\n", (unsigned) numBytes);
742 
743  char *start = PyByteArray_AsString(byteObj);
744  assert(start);
745  char *bytes = start;
746  PyObject *result = NULL;
747 
748  // Generate a list of messages found
749  while(numBytes) {
750  char c = *bytes++;
751  numBytes--;
752  get_expectedlength(self); mavdebug("parse 0x%x\n", (unsigned char) c);
753 
754  if (py_mavlink_parse_char(c, &self->msg, &self->mav_status)) {
755  mavdebug("got packet\n");
756  result = msg_to_py(self->MAVLinkMessage, &self->msg);
757  if(result != NULL)
758  break;
759  }
760  }
761 
762  // We didn't process all bytes provided by the caller, so fixup their array
763  memmove(start, bytes, numBytes);
764  PyByteArray_Resize(byteObj, numBytes);
765 
766  if(result != NULL)
767  return result;
768  else
769  return createPyNone();
770 
772 }
773 
781 static PyObject *
783 {
785 
786  mavdebug("Enter py_parse_buffer\n");
787 
788  const char *bytes;
789  Py_ssize_t numBytes = 0;
790 
791  if (!PyArg_ParseTuple(args, "s#", &bytes, &numBytes)) {
792  set_pyerror("Invalid arguments");
793  return NULL;
794  }
795 
796  // mavdebug("numbytes %u\n", (unsigned) numBytes);
797 
798  PyObject* list = PyList_New(0);
799 
800  // Generate a list of messages found
801  while(numBytes--) {
802  char c = *bytes++;
803  // mavdebug("parse %c\n", c);
804 
805  if (py_mavlink_parse_char(c, &self->msg, &self->mav_status)) {
806  PyObject *obj = msg_to_py(self->MAVLinkMessage, &self->msg);
807  if(obj != NULL) {
808  PyList_Append(list, obj);
809 
810  // Append will have bummped up the ref count on obj, so we need to release our count
811  Py_DECREF(obj);
812  }
813  }
814  }
815 
816  return list;
817 
819 }
820 
821 static PyObject *
822 NativeConnection_new(PyTypeObject *type, PyObject *args, PyObject *kwds)
823 {
824  NativeConnection *self = (NativeConnection *)type->tp_alloc(type, 0);
825 
826  mavdebug("new connection\n");
827  return (PyObject *)self;
828 }
829 
830 
831 static int
832 NativeConnection_init(NativeConnection *self, PyObject *args, PyObject *kwds)
833 {
835 
836  mavdebug("Enter init\n");
837 
838  memset(&self->mav_status, 0, sizeof(self->mav_status));
839 
840  PyObject* msgclass, *mavlink_map;
841  if (!PyArg_ParseTuple(args, "OO", &msgclass, &mavlink_map)) {
842  set_pyerror("Invalid arguments");
843  return -1;
844  }
845 
846  // keep a ref to our mavlink instance constructor
847  assert(msgclass);
848  self->MAVLinkMessage = msgclass;
849  Py_INCREF(msgclass);
850 
851  assert(mavlink_map);
852  if(!info_inited) {
853  init_message_info(mavlink_map);
854  info_inited = TRUE;
855  }
856 
857  mavdebug("inited connection\n");
858  return 0;
859 
861 }
862 
864 {
865  Py_XDECREF(self->MAVLinkMessage);
866  Py_TYPE(self)->tp_free((PyObject*)self);
867 }
868 
869 static PyMemberDef NativeConnection_members[] = {
870  {NULL} /* Sentinel */
871 };
872 
873 static PyGetSetDef NativeConnection_getseters[] = {
874  {"expected_length",
876  "How many characters would the state-machine like to read now",
877  NULL},
878  {NULL} /* Sentinel */
879 };
880 
881 static PyMethodDef NativeConnection_methods[] = {
882  {"parse_chars", (PyCFunction) py_parse_chars, METH_VARARGS,
883  "Given a msg class and an array of bytes, Parse chars, returning a message or None"},
884  {"parse_buffer", (PyCFunction) py_parse_buffer, METH_VARARGS,
885  "Given a msg class and a string like object, Parse chars, returning a (possibly empty) list of messages"},
886  {NULL, NULL},
887 };
888 
889 // FIXME - delete this?
890 static PyTypeObject NativeConnectionType = {
891 #if PY_MAJOR_VERSION >= 3
892  PyVarObject_HEAD_INIT(NULL, 0)
893 #else
894  PyObject_HEAD_INIT(NULL)
895  0, /* ob_size */
896 #endif
897  "mavnative.NativeConnection", /* tp_name */
898  sizeof(NativeConnection), /* tp_basicsize */
899  0, /* tp_itemsize */
900  (destructor)NativeConnection_dealloc, /* tp_dealloc */
901  0, /* tp_print */
902  0, /* tp_getattr */
903  0, /* tp_setattr */
904  0, /* tp_compare */
905  0, /* tp_repr */
906  0, /* tp_as_number */
907  0, /* tp_as_sequence */
908  0, /* tp_as_mapping */
909  0, /* tp_hash */
910  0, /* tp_call */
911  0, /* tp_str */
912  0, /* tp_getattro */
913  0, /* tp_setattro */
914  0, /* tp_as_buffer */
915  Py_TPFLAGS_DEFAULT |
916  Py_TPFLAGS_BASETYPE, /* tp_flags */
917  "NativeConnection objects", /* tp_doc */
918  0, /* tp_traverse */
919  0, /* tp_clear */
920  0, /* tp_richcompare */
921  0, /* tp_weaklistoffset */
922  0, /* tp_iter */
923  0, /* tp_iternext */
924  NativeConnection_methods, /* tp_methods */
925  NativeConnection_members, /* tp_members */
926  NativeConnection_getseters, /* tp_getset */
927  0, /* tp_base */
928  0, /* tp_dict */
929  0, /* tp_descr_get */
930  0, /* tp_descr_set */
931  0, /* tp_dictoffset */
932  (initproc)NativeConnection_init, /* tp_init */
933  0, /* tp_alloc */
934  NativeConnection_new, /* tp_new */
935 };
936 
937 #if PY_MAJOR_VERSION >= 3
938 #define MOD_RETURN(m) return m
939 #else
940 #define MOD_RETURN(m) return
941 #endif
942 
943 PyMODINIT_FUNC
944 #if PY_MAJOR_VERSION >= 3
945  PyInit_mavnative(void)
946 #else
948 #endif
949 {
950  if (PyType_Ready(&NativeConnectionType) < 0)
951  MOD_RETURN(NULL);
952 
953 #if PY_MAJOR_VERSION < 3
954  static PyMethodDef ModuleMethods[] = {
955  {NULL, NULL, 0, NULL} /* Sentinel */
956  };
957 
958  PyObject *m = Py_InitModule3("mavnative", ModuleMethods, "Mavnative module");
959  if (m == NULL)
960  MOD_RETURN(m);
961 #else
962  static PyModuleDef mod_def = {
963  PyModuleDef_HEAD_INIT,
964  "mavnative",
965  "EMavnative module",
966  -1,
967  NULL, NULL, NULL, NULL, NULL
968  };
969 
970  PyObject *m = PyModule_Create(&mod_def);
971 #endif
972 
973  MAVNativeError = PyErr_NewException("mavnative.error", NULL, NULL);
974  Py_INCREF(MAVNativeError);
975  PyModule_AddObject(m, "error", MAVNativeError);
976 
977  Py_INCREF(&NativeConnectionType);
978  PyModule_AddObject(m, "NativeConnection", (PyObject *) &NativeConnectionType);
979  MOD_RETURN(m);
980 }
static PyObject * NativeConnection_getexpectedlength(NativeConnection *self, void *closure)
Definition: mavnative.c:719
static PyObject * py_parse_chars(NativeConnection *self, PyObject *args)
Definition: mavnative.c:729
static void set_pyerror(const char *msg)
Definition: mavnative.c:320
static PyObject * py_parse_buffer(NativeConnection *self, PyObject *args)
Definition: mavnative.c:782
py_message_t msg
Definition: mavnative.c:109
static PyObject * NativeConnection_new(PyTypeObject *type, PyObject *args, PyObject *kwds)
Definition: mavnative.c:822
#define MAVLINK_MESSAGE_LENGTH(msgid)
Definition: mavnative.c:64
mavlink_message_type_t type
Definition: mavnative.c:73
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static void init_message_info(PyObject *mavlink_map)
Definition: mavnative.c:425
MAVLINK_HELPER uint8_t py_mavlink_parse_char(uint8_t c, py_message_t *pymsg, mavlink_status_t *status)
Definition: mavnative.c:147
#define MOD_RETURN(m)
Definition: mavnative.c:940
#define PYTHON_EXIT_INT
Definition: mavnative.c:127
#define mavdebug(x...)
Definition: mavnative.c:116
static PyObject * msg_to_py(PyObject *msgclass, const py_message_t *pymsg)
Definition: mavnative.c:614
static py_message_info_t py_message_info[256]
Definition: mavnative.c:90
#define MAVLINK_MESSAGE_CRC(msgid)
Definition: mavnative.c:55
#define PyByteString_ConcatAndDel
Definition: mavnative.c:30
static PyObject * pyextract_mavlink(const mavlink_message_t *msg, const py_field_info_t *field)
Definition: mavnative.c:518
#define FALSE
Definition: mavnative.c:69
static PyObject * createPyNone(void)
Definition: mavnative.c:494
static void set_attribute(PyObject *obj, const char *attrName, PyObject *val)
Definition: mavnative.c:505
static int get_py_typeinfo(char type_char, int array_size, unsigned *wire_offset)
Definition: mavnative.c:389
static void NativeConnection_dealloc(NativeConnection *self)
Definition: mavnative.c:863
static int NativeConnection_init(NativeConnection *self, PyObject *args, PyObject *kwds)
Definition: mavnative.c:832
unsigned int wire_offset
Definition: mavnative.c:75
static jmp_buf python_entry
Definition: mavnative.c:123
#define _MAV_RETURN_int8_t(msg, wire_offset)
PyObject * id
Definition: mavnative.c:81
#define _MAV_RETURN_char(msg, wire_offset)
static unsigned get_field_size(int field_type)
Definition: mavnative.c:336
PyObject * name
Definition: mavnative.c:82
uint8_t bytes[MAVLINK_MAX_PACKET_LEN]
Definition: mavnative.c:101
static mavlink_system_t mavlink_system
Definition: mavnative.c:41
void __assert_fail(const char *__assertion, const char *__file, unsigned int __line, const char *__function)
Definition: mavnative.c:325
static PyGetSetDef NativeConnection_getseters[]
Definition: mavnative.c:873
static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
Definition: mavnative.c:42
#define TRUE
Definition: mavnative.c:68
static PyMemberDef NativeConnection_members[]
Definition: mavnative.c:869
mavlink_status_t mav_status
Definition: mavnative.c:108
#define PYTHON_ENTRY
Definition: mavnative.c:125
mavlink_message_t msg
Definition: mavnative.c:99
static PyObject * MAVNativeError
Definition: mavnative.c:121
unsigned num_fields
Definition: mavnative.c:85
unsigned len
Definition: mavnative.c:83
py_field_info_t fields[MAVLINK_MAX_FIELDS]
Definition: mavnative.c:87
unsigned int array_length
Definition: mavnative.c:74
PyObject * fieldnames
Definition: mavnative.c:86
static uint8_t info_inited
Definition: mavnative.c:91
PyObject_HEAD PyObject * MAVLinkMessage
Definition: mavnative.c:107
#define PyByteString_FromStringAndSize
Definition: mavnative.c:29
#define PYTHON_EXIT
Definition: mavnative.c:126
static PyTypeObject NativeConnectionType
Definition: mavnative.c:890
uint8_t crc_extra
Definition: mavnative.c:84
static PyMethodDef NativeConnection_methods[]
Definition: mavnative.c:881
PyObject * name
Definition: mavnative.c:72
static int get_expectedlength(NativeConnection *self)
Definition: mavnative.c:673
#define PyByteString_FromString
Definition: mavnative.c:28
PyMODINIT_FUNC initmavnative(void)
Definition: mavnative.c:947


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02