mavgen_c.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 parse a MAVLink protocol XML file and generate a C implementation
4 
5 Copyright Andrew Tridgell 2011
6 Released under GNU GPL version 3 or later
7 '''
8 from __future__ import print_function
9 from future.utils import iteritems
10 
11 from builtins import range
12 from builtins import object
13 
14 import os
15 from . import mavparse, mavtemplate
16 
18 
19 def generate_version_h(directory, xml):
20  '''generate version.h'''
21  f = open(os.path.join(directory, "version.h"), mode='w')
22  t.write(f,'''
23 /** @file
24  * @brief MAVLink comm protocol built from ${basename}.xml
25  * @see http://mavlink.org
26  */
27 #pragma once
28 
29 #ifndef MAVLINK_VERSION_H
30 #define MAVLINK_VERSION_H
31 
32 #define MAVLINK_BUILD_DATE "${parse_time}"
33 #define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}"
34 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload}
35 
36 #endif // MAVLINK_VERSION_H
37 ''', xml)
38  f.close()
39 
40 def generate_mavlink_h(directory, xml):
41  '''generate mavlink.h'''
42  f = open(os.path.join(directory, "mavlink.h"), mode='w')
43  t.write(f,'''
44 /** @file
45  * @brief MAVLink comm protocol built from ${basename}.xml
46  * @see http://mavlink.org
47  */
48 #pragma once
49 #ifndef MAVLINK_H
50 #define MAVLINK_H
51 
52 #define MAVLINK_PRIMARY_XML_IDX ${xml_idx}
53 
54 #ifndef MAVLINK_STX
55 #define MAVLINK_STX ${protocol_marker}
56 #endif
57 
58 #ifndef MAVLINK_ENDIAN
59 #define MAVLINK_ENDIAN ${mavlink_endian}
60 #endif
61 
62 #ifndef MAVLINK_ALIGNED_FIELDS
63 #define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define}
64 #endif
65 
66 #ifndef MAVLINK_CRC_EXTRA
67 #define MAVLINK_CRC_EXTRA ${crc_extra_define}
68 #endif
69 
70 #ifndef MAVLINK_COMMAND_24BIT
71 #define MAVLINK_COMMAND_24BIT ${command_24bit_define}
72 #endif
73 
74 #include "version.h"
75 #include "${basename}.h"
76 
77 #endif // MAVLINK_H
78 ''', xml)
79  f.close()
80 
81 def generate_main_h(directory, xml):
82  '''generate main header per XML file'''
83  f = open(os.path.join(directory, xml.basename + ".h"), mode='w')
84  t.write(f, '''
85 /** @file
86  * @brief MAVLink comm protocol generated from ${basename}.xml
87  * @see http://mavlink.org
88  */
89 #pragma once
90 #ifndef MAVLINK_${basename_upper}_H
91 #define MAVLINK_${basename_upper}_H
92 
93 #ifndef MAVLINK_H
94  #error Wrong include order: MAVLINK_${basename_upper}.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
95 #endif
96 
97 #undef MAVLINK_THIS_XML_IDX
98 #define MAVLINK_THIS_XML_IDX ${xml_idx}
99 
100 #ifdef __cplusplus
101 extern "C" {
102 #endif
103 
104 // MESSAGE LENGTHS AND CRCS
105 
106 #ifndef MAVLINK_MESSAGE_LENGTHS
107 #define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}}
108 #endif
109 
110 #ifndef MAVLINK_MESSAGE_CRCS
111 #define MAVLINK_MESSAGE_CRCS {${message_crcs_array}}
112 #endif
113 
114 #include "../protocol.h"
115 
116 #define MAVLINK_ENABLED_${basename_upper}
117 
118 // ENUM DEFINITIONS
119 
120 ${{enum:
121 /** @brief ${description} */
122 #ifndef HAVE_ENUM_${name}
123 #define HAVE_ENUM_${name}
124 typedef enum ${name}
125 {
126 ${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */
127 }}
128 } ${name};
129 #endif
130 }}
131 
132 // MAVLINK VERSION
133 
134 #ifndef MAVLINK_VERSION
135 #define MAVLINK_VERSION ${version}
136 #endif
137 
138 #if (MAVLINK_VERSION == 0)
139 #undef MAVLINK_VERSION
140 #define MAVLINK_VERSION ${version}
141 #endif
142 
143 // MESSAGE DEFINITIONS
144 ${{message:#include "./mavlink_msg_${name_lower}.h"
145 }}
146 
147 // base include
148 ${{include_list:#include "../${base}/${base}.h"
149 }}
150 
151 #undef MAVLINK_THIS_XML_IDX
152 #define MAVLINK_THIS_XML_IDX ${xml_idx}
153 
154 #if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX
155 # define MAVLINK_MESSAGE_INFO {${message_info_array}}
156 # define MAVLINK_MESSAGE_NAMES {${message_name_array}}
157 # if MAVLINK_COMMAND_24BIT
158 # include "../mavlink_get_info.h"
159 # endif
160 #endif
161 
162 #ifdef __cplusplus
163 }
164 #endif // __cplusplus
165 #endif // MAVLINK_${basename_upper}_H
166 ''', xml)
167 
168  f.close()
169 
170 
171 def generate_message_h(directory, m):
172  '''generate per-message header for a XML file'''
173  f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w')
174  t.write(f, '''
175 #pragma once
176 // MESSAGE ${name} PACKING
177 
178 #define MAVLINK_MSG_ID_${name} ${id}
179 
180 MAVPACKED(
181 typedef struct __mavlink_${name_lower}_t {
182 ${{ordered_fields: ${type} ${name}${array_suffix}; /*< ${units} ${description}*/
183 }}
184 }) mavlink_${name_lower}_t;
185 
186 #define MAVLINK_MSG_ID_${name}_LEN ${wire_length}
187 #define MAVLINK_MSG_ID_${name}_MIN_LEN ${wire_min_length}
188 #define MAVLINK_MSG_ID_${id}_LEN ${wire_length}
189 #define MAVLINK_MSG_ID_${id}_MIN_LEN ${wire_min_length}
190 
191 #define MAVLINK_MSG_ID_${name}_CRC ${crc_extra}
192 #define MAVLINK_MSG_ID_${id}_CRC ${crc_extra}
193 
194 ${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length}
195 }}
196 
197 #if MAVLINK_COMMAND_24BIT
198 #define MAVLINK_MESSAGE_INFO_${name} { \\
199  ${id}, \\
200  "${name}", \\
201  ${num_fields}, \\
202  { ${{fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
203  }} } \\
204 }
205 #else
206 #define MAVLINK_MESSAGE_INFO_${name} { \\
207  "${name}", \\
208  ${num_fields}, \\
209  { ${{fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
210  }} } \\
211 }
212 #endif
213 
214 /**
215  * @brief Pack a ${name_lower} message
216  * @param system_id ID of this system
217  * @param component_id ID of this component (e.g. 200 for IMU)
218  * @param msg The MAVLink message to compress the data into
219  *
220 ${{arg_fields: * @param ${name} ${units} ${description}
221 }}
222  * @return length of the message in bytes (excluding serial stream start sign)
223  */
224 static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
225  ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
226 {
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
228  char buf[MAVLINK_MSG_ID_${name}_LEN];
229 ${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
230 }}
231 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
232 }}
233  memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN);
234 #else
235  mavlink_${name_lower}_t packet;
236 ${{scalar_fields: packet.${name} = ${putname};
237 }}
238 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
239 }}
240  memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN);
241 #endif
242 
243  msg->msgid = MAVLINK_MSG_ID_${name};
244  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
245 }
246 
247 /**
248  * @brief Pack a ${name_lower} message on a channel
249  * @param system_id ID of this system
250  * @param component_id ID of this component (e.g. 200 for IMU)
251  * @param chan The MAVLink channel this message will be sent over
252  * @param msg The MAVLink message to compress the data into
253 ${{arg_fields: * @param ${name} ${units} ${description}
254 }}
255  * @return length of the message in bytes (excluding serial stream start sign)
256  */
257 static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
258  mavlink_message_t* msg,
259  ${{arg_fields:${array_const}${type} ${array_prefix}${name},}})
260 {
261 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
262  char buf[MAVLINK_MSG_ID_${name}_LEN];
263 ${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
264 }}
265 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
266 }}
267  memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN);
268 #else
269  mavlink_${name_lower}_t packet;
270 ${{scalar_fields: packet.${name} = ${putname};
271 }}
272 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
273 }}
274  memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN);
275 #endif
276 
277  msg->msgid = MAVLINK_MSG_ID_${name};
278  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
279 }
280 
281 /**
282  * @brief Encode a ${name_lower} struct
283  *
284  * @param system_id ID of this system
285  * @param component_id ID of this component (e.g. 200 for IMU)
286  * @param msg The MAVLink message to compress the data into
287  * @param ${name_lower} C-struct to read the message contents from
288  */
289 static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower})
290 {
291  return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}});
292 }
293 
294 /**
295  * @brief Encode a ${name_lower} struct on a channel
296  *
297  * @param system_id ID of this system
298  * @param component_id ID of this component (e.g. 200 for IMU)
299  * @param chan The MAVLink channel this message will be sent over
300  * @param msg The MAVLink message to compress the data into
301  * @param ${name_lower} C-struct to read the message contents from
302  */
303 static inline uint16_t mavlink_msg_${name_lower}_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower})
304 {
305  return mavlink_msg_${name_lower}_pack_chan(system_id, component_id, chan, msg,${{arg_fields: ${name_lower}->${name},}});
306 }
307 
308 /**
309  * @brief Send a ${name_lower} message
310  * @param chan MAVLink channel to send the message
311  *
312 ${{arg_fields: * @param ${name} ${units} ${description}
313 }}
314  */
315 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
316 
317 static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
318 {
319 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
320  char buf[MAVLINK_MSG_ID_${name}_LEN];
321 ${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
322 }}
323 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
324 }}
325  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
326 #else
327  mavlink_${name_lower}_t packet;
328 ${{scalar_fields: packet.${name} = ${putname};
329 }}
330 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
331 }}
332  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
333 #endif
334 }
335 
336 /**
337  * @brief Send a ${name_lower} message
338  * @param chan MAVLink channel to send the message
339  * @param struct The MAVLink struct to serialize
340  */
341 static inline void mavlink_msg_${name_lower}_send_struct(mavlink_channel_t chan, const mavlink_${name_lower}_t* ${name_lower})
342 {
343 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
344  mavlink_msg_${name_lower}_send(chan,${{arg_fields: ${name_lower}->${name},}});
345 #else
346  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)${name_lower}, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
347 #endif
348 }
349 
350 #if MAVLINK_MSG_ID_${name}_LEN <= MAVLINK_MAX_PAYLOAD_LEN
351 /*
352  This varient of _send() can be used to save stack space by re-using
353  memory from the receive buffer. The caller provides a
354  mavlink_message_t which is the size of a full mavlink message. This
355  is usually the receive buffer for the channel, and allows a reply to an
356  incoming message with minimum stack space usage.
357  */
358 static inline void mavlink_msg_${name_lower}_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
359 {
360 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
361  char *buf = (char *)msgbuf;
362 ${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
363 }}
364 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
365 }}
366  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
367 #else
368  mavlink_${name_lower}_t *packet = (mavlink_${name_lower}_t *)msgbuf;
369 ${{scalar_fields: packet->${name} = ${putname};
370 }}
371 ${{array_fields: mav_array_memcpy(packet->${name}, ${name}, sizeof(${type})*${array_length});
372 }}
373  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)packet, MAVLINK_MSG_ID_${name}_MIN_LEN, MAVLINK_MSG_ID_${name}_LEN, MAVLINK_MSG_ID_${name}_CRC);
374 #endif
375 }
376 #endif
377 
378 #endif
379 
380 // MESSAGE ${name} UNPACKING
381 
382 ${{fields:
383 /**
384  * @brief Get field ${name} from ${name_lower} message
385  *
386  * @return ${units} ${description}
387  */
388 static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg})
389 {
390  return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset});
391 }
392 }}
393 
394 /**
395  * @brief Decode a ${name_lower} message into a struct
396  *
397  * @param msg The message to decode
398  * @param ${name_lower} C-struct to decode the message contents into
399  */
400 static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower})
401 {
402 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
403 ${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right});
404 }}
405 #else
406  uint8_t len = msg->len < MAVLINK_MSG_ID_${name}_LEN? msg->len : MAVLINK_MSG_ID_${name}_LEN;
407  memset(${name_lower}, 0, MAVLINK_MSG_ID_${name}_LEN);
408  memcpy(${name_lower}, _MAV_PAYLOAD(msg), len);
409 #endif
410 }
411 ''', m)
412  f.close()
413 
414 
415 def generate_testsuite_h(directory, xml):
416  '''generate testsuite.h per XML file'''
417  f = open(os.path.join(directory, "testsuite.h"), mode='w')
418  t.write(f, '''
419 /** @file
420  * @brief MAVLink comm protocol testsuite generated from ${basename}.xml
421  * @see http://qgroundcontrol.org/mavlink/
422  */
423 #pragma once
424 #ifndef ${basename_upper}_TESTSUITE_H
425 #define ${basename_upper}_TESTSUITE_H
426 
427 #ifdef __cplusplus
428 extern "C" {
429 #endif
430 
431 #ifndef MAVLINK_TEST_ALL
432 #define MAVLINK_TEST_ALL
433 ${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg);
434 }}
435 static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg);
436 
437 static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
438 {
439 ${{include_list: mavlink_test_${base}(system_id, component_id, last_msg);
440 }}
441  mavlink_test_${basename}(system_id, component_id, last_msg);
442 }
443 #endif
444 
445 ${{include_list:#include "../${base}/testsuite.h"
446 }}
447 
448 ${{message:
449 static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
450 {
451 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
452  mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
453  if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_${name} >= 256) {
454  return;
455  }
456 #endif
457  mavlink_message_t msg;
458  uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
459  uint16_t i;
460  mavlink_${name_lower}_t packet_in = {
461  ${{ordered_fields:${c_test_value},}}
462  };
463  mavlink_${name_lower}_t packet1, packet2;
464  memset(&packet1, 0, sizeof(packet1));
465  ${{scalar_fields:packet1.${name} = packet_in.${name};
466  }}
467  ${{array_fields:mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length});
468  }}
469 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
470  if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
471  // cope with extensions
472  memset(MAVLINK_MSG_ID_${name}_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_${name}_MIN_LEN);
473  }
474 #endif
475  memset(&packet2, 0, sizeof(packet2));
476  mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1);
477  mavlink_msg_${name_lower}_decode(&msg, &packet2);
478  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
479 
480  memset(&packet2, 0, sizeof(packet2));
481  mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }});
482  mavlink_msg_${name_lower}_decode(&msg, &packet2);
483  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
484 
485  memset(&packet2, 0, sizeof(packet2));
486  mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }});
487  mavlink_msg_${name_lower}_decode(&msg, &packet2);
488  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
489 
490  memset(&packet2, 0, sizeof(packet2));
491  mavlink_msg_to_send_buffer(buffer, &msg);
492  for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
493  comm_send_ch(MAVLINK_COMM_0, buffer[i]);
494  }
495  mavlink_msg_${name_lower}_decode(last_msg, &packet2);
496  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
497 
498  memset(&packet2, 0, sizeof(packet2));
499  mavlink_msg_${name_lower}_send(MAVLINK_COMM_1 ${{arg_fields:, packet1.${name} }});
500  mavlink_msg_${name_lower}_decode(last_msg, &packet2);
501  MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
502 }
503 }}
504 
505 static void mavlink_test_${basename}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
506 {
507 ${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg);
508 }}
509 }
510 
511 #ifdef __cplusplus
512 }
513 #endif // __cplusplus
514 #endif // ${basename_upper}_TESTSUITE_H
515 ''', xml)
516 
517  f.close()
518 
519 def copy_fixed_headers(directory, xml):
520  '''copy the fixed protocol headers to the target directory'''
521  import shutil, filecmp
522  hlist = {
523  "0.9": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h' ],
524  "1.0": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_conversions.h' ],
525  "2.0": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_conversions.h',
526  'mavlink_get_info.h', 'mavlink_sha256.h' ]
527  }
528  basepath = os.path.dirname(os.path.realpath(__file__))
529  srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version)
530  print("Copying fixed headers for protocol %s to %s" % (xml.wire_protocol_version, directory))
531  for h in hlist[xml.wire_protocol_version]:
532  src = os.path.realpath(os.path.join(srcpath, h))
533  dest = os.path.realpath(os.path.join(directory, h))
534  if src == dest or (os.path.exists(dest) and filecmp.cmp(src, dest)):
535  continue
536  shutil.copy(src, dest)
537 
538 class mav_include(object):
539  def __init__(self, base):
540  self.base = base
541 
542 def generate_one(basename, xml):
543  '''generate headers for one XML file'''
544 
545  directory = os.path.join(basename, xml.basename)
546 
547  print("Generating C implementation in directory %s" % directory)
548  mavparse.mkdir_p(directory)
549 
550  if xml.little_endian:
551  xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
552  else:
553  xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
554 
555  if xml.crc_extra:
556  xml.crc_extra_define = "1"
557  else:
558  xml.crc_extra_define = "0"
559 
560  if xml.command_24bit:
561  xml.command_24bit_define = "1"
562  else:
563  xml.command_24bit_define = "0"
564 
565  if xml.sort_fields:
566  xml.aligned_fields_define = "1"
567  else:
568  xml.aligned_fields_define = "0"
569 
570  # work out the included headers
571  xml.include_list = []
572  for i in xml.include:
573  base = i[:-4]
574  xml.include_list.append(mav_include(base))
575 
576  # form message lengths array
577  xml.message_lengths_array = ''
578  if not xml.command_24bit:
579  for msgid in range(256):
580  mlen = xml.message_min_lengths.get(msgid, 0)
581  xml.message_lengths_array += '%u, ' % mlen
582  xml.message_lengths_array = xml.message_lengths_array[:-2]
583 
584  # and message CRCs array
585  xml.message_crcs_array = ''
586  if xml.command_24bit:
587  # we sort with primary key msgid
588  for msgid in sorted(xml.message_crcs.keys()):
589  xml.message_crcs_array += '{%u, %u, %u, %u, %u, %u}, ' % (msgid,
590  xml.message_crcs[msgid],
591  xml.message_min_lengths[msgid],
592  xml.message_flags[msgid],
593  xml.message_target_system_ofs[msgid],
594  xml.message_target_component_ofs[msgid])
595  else:
596  for msgid in range(256):
597  crc = xml.message_crcs.get(msgid, 0)
598  xml.message_crcs_array += '%u, ' % crc
599  xml.message_crcs_array = xml.message_crcs_array[:-2]
600 
601  # form message info array
602  xml.message_info_array = ''
603  if xml.command_24bit:
604  # we sort with primary key msgid
605  for msgid in sorted(xml.message_names.keys()):
606  name = xml.message_names[msgid]
607  xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
608  else:
609  for msgid in range(256):
610  name = xml.message_names.get(msgid, None)
611  if name is not None:
612  xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
613  else:
614  # Several C compilers don't accept {NULL} for
615  # multi-dimensional arrays and structs
616  # feed the compiler a "filled" empty message
617  xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
618  xml.message_info_array = xml.message_info_array[:-2]
619 
620  # form message name array
621  xml.message_name_array = ''
622  # sort by names
623  for msgid, name in sorted(iteritems(xml.message_names), key=lambda k_v: (k_v[1], k_v[0])):
624  xml.message_name_array += '{ "%s", %u }, ' % (name, msgid)
625  xml.message_name_array = xml.message_name_array[:-2]
626 
627  # add some extra field attributes for convenience with arrays
628  for m in xml.message:
629  m.msg_name = m.name
630  if xml.crc_extra:
631  m.crc_extra_arg = ", %s" % m.crc_extra
632  else:
633  m.crc_extra_arg = ""
634  for f in m.fields:
635  if f.print_format is None:
636  f.c_print_format = 'NULL'
637  else:
638  f.c_print_format = '"%s"' % f.print_format
639  if f.array_length != 0:
640  f.array_suffix = '[%u]' % f.array_length
641  f.array_prefix = '*'
642  f.array_tag = '_array'
643  f.array_arg = ', %u' % f.array_length
644  f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
645  f.array_const = 'const '
646  f.decode_left = ''
647  f.decode_right = ', %s->%s' % (m.name_lower, f.name)
648  f.return_type = 'uint16_t'
649  f.get_arg = ', %s *%s' % (f.type, f.name)
650  if f.type == 'char':
651  f.c_test_value = '"%s"' % f.test_value
652  else:
653  test_strings = []
654  for v in f.test_value:
655  test_strings.append(str(v))
656  f.c_test_value = '{ %s }' % ', '.join(test_strings)
657  else:
658  f.array_suffix = ''
659  f.array_prefix = ''
660  f.array_tag = ''
661  f.array_arg = ''
662  f.array_return_arg = ''
663  f.array_const = ''
664  f.decode_left = "%s->%s = " % (m.name_lower, f.name)
665  f.decode_right = ''
666  f.get_arg = ''
667  f.return_type = f.type
668  if f.type == 'char':
669  f.c_test_value = "'%s'" % f.test_value
670  elif f.type == 'uint64_t':
671  f.c_test_value = "%sULL" % f.test_value
672  elif f.type == 'int64_t':
673  f.c_test_value = "%sLL" % f.test_value
674  else:
675  f.c_test_value = f.test_value
676 
677  # cope with uint8_t_mavlink_version
678  for m in xml.message:
679  m.arg_fields = []
680  m.array_fields = []
681  m.scalar_fields = []
682  for f in m.ordered_fields:
683  if f.array_length != 0:
684  m.array_fields.append(f)
685  else:
686  m.scalar_fields.append(f)
687  for f in m.fields:
688  if not f.omit_arg:
689  m.arg_fields.append(f)
690  f.putname = f.name
691  else:
692  f.putname = f.const_value
693 
694  generate_mavlink_h(directory, xml)
695  generate_version_h(directory, xml)
696  generate_main_h(directory, xml)
697  for m in xml.message:
698  generate_message_h(directory, m)
699  generate_testsuite_h(directory, xml)
700 
701 
702 def generate(basename, xml_list):
703  '''generate complete MAVLink C implemenation'''
704 
705  for idx in range(len(xml_list)):
706  xml = xml_list[idx]
707  xml.xml_idx = idx
708  generate_one(basename, xml)
709  copy_fixed_headers(basename, xml_list[0])


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