3 parse a MAVLink protocol XML file and generate a C implementation 5 Copyright Andrew Tridgell 2011 6 Released under GNU GPL version 3 or later 8 from __future__
import print_function
9 from future.utils
import iteritems
11 from builtins
import range
12 from builtins
import object
15 from .
import mavparse, mavtemplate
20 '''generate version.h''' 21 f = open(os.path.join(directory,
"version.h"), mode=
'w')
24 * @brief MAVLink comm protocol built from ${basename}.xml 25 * @see http://mavlink.org 29 #ifndef MAVLINK_VERSION_H 30 #define MAVLINK_VERSION_H 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} 36 #endif // MAVLINK_VERSION_H 41 '''generate mavlink.h''' 42 f = open(os.path.join(directory,
"mavlink.h"), mode=
'w')
45 * @brief MAVLink comm protocol built from ${basename}.xml 46 * @see http://mavlink.org 52 #define MAVLINK_PRIMARY_XML_IDX ${xml_idx} 55 #define MAVLINK_STX ${protocol_marker} 58 #ifndef MAVLINK_ENDIAN 59 #define MAVLINK_ENDIAN ${mavlink_endian} 62 #ifndef MAVLINK_ALIGNED_FIELDS 63 #define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define} 66 #ifndef MAVLINK_CRC_EXTRA 67 #define MAVLINK_CRC_EXTRA ${crc_extra_define} 70 #ifndef MAVLINK_COMMAND_24BIT 71 #define MAVLINK_COMMAND_24BIT ${command_24bit_define} 75 #include "${basename}.h" 82 '''generate main header per XML file''' 83 f = open(os.path.join(directory, xml.basename +
".h"), mode=
'w')
86 * @brief MAVLink comm protocol generated from ${basename}.xml 87 * @see http://mavlink.org 90 #ifndef MAVLINK_${basename_upper}_H 91 #define MAVLINK_${basename_upper}_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. 97 #undef MAVLINK_THIS_XML_IDX 98 #define MAVLINK_THIS_XML_IDX ${xml_idx} 104 // MESSAGE LENGTHS AND CRCS 106 #ifndef MAVLINK_MESSAGE_LENGTHS 107 #define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}} 110 #ifndef MAVLINK_MESSAGE_CRCS 111 #define MAVLINK_MESSAGE_CRCS {${message_crcs_array}} 114 #include "../protocol.h" 116 #define MAVLINK_ENABLED_${basename_upper} 121 /** @brief ${description} */ 122 #ifndef HAVE_ENUM_${name} 123 #define HAVE_ENUM_${name} 126 ${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */ 134 #ifndef MAVLINK_VERSION 135 #define MAVLINK_VERSION ${version} 138 #if (MAVLINK_VERSION == 0) 139 #undef MAVLINK_VERSION 140 #define MAVLINK_VERSION ${version} 143 // MESSAGE DEFINITIONS 144 ${{message:#include "./mavlink_msg_${name_lower}.h" 148 ${{include_list:#include "../${base}/${base}.h" 151 #undef MAVLINK_THIS_XML_IDX 152 #define MAVLINK_THIS_XML_IDX ${xml_idx} 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" 164 #endif // __cplusplus 165 #endif // MAVLINK_${basename_upper}_H 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')
176 // MESSAGE ${name} PACKING 178 #define MAVLINK_MSG_ID_${name} ${id} 181 typedef struct __mavlink_${name_lower}_t { 182 ${{ordered_fields: ${type} ${name}${array_suffix}; /*< ${units} ${description}*/ 184 }) mavlink_${name_lower}_t; 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} 191 #define MAVLINK_MSG_ID_${name}_CRC ${crc_extra} 192 #define MAVLINK_MSG_ID_${id}_CRC ${crc_extra} 194 ${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length} 197 #if MAVLINK_COMMAND_24BIT 198 #define MAVLINK_MESSAGE_INFO_${name} { \\ 202 { ${{fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\ 206 #define MAVLINK_MESSAGE_INFO_${name} { \\ 209 { ${{fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\ 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 220 ${{arg_fields: * @param ${name} ${units} ${description} 222 * @return length of the message in bytes (excluding serial stream start sign) 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},}}) 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}); 231 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); 233 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN); 235 mavlink_${name_lower}_t packet; 236 ${{scalar_fields: packet.${name} = ${putname}; 238 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); 240 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN); 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); 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} 255 * @return length of the message in bytes (excluding serial stream start sign) 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},}}) 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}); 265 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); 267 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN); 269 mavlink_${name_lower}_t packet; 270 ${{scalar_fields: packet.${name} = ${putname}; 272 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); 274 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN); 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); 282 * @brief Encode a ${name_lower} struct 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 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}) 291 return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}}); 295 * @brief Encode a ${name_lower} struct on a channel 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 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}) 305 return mavlink_msg_${name_lower}_pack_chan(system_id, component_id, chan, msg,${{arg_fields: ${name_lower}->${name},}}); 309 * @brief Send a ${name_lower} message 310 * @param chan MAVLink channel to send the message 312 ${{arg_fields: * @param ${name} ${units} ${description} 315 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 317 static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) 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}); 323 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); 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); 327 mavlink_${name_lower}_t packet; 328 ${{scalar_fields: packet.${name} = ${putname}; 330 ${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); 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); 337 * @brief Send a ${name_lower} message 338 * @param chan MAVLink channel to send the message 339 * @param struct The MAVLink struct to serialize 341 static inline void mavlink_msg_${name_lower}_send_struct(mavlink_channel_t chan, const mavlink_${name_lower}_t* ${name_lower}) 343 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 344 mavlink_msg_${name_lower}_send(chan,${{arg_fields: ${name_lower}->${name},}}); 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); 350 #if MAVLINK_MSG_ID_${name}_LEN <= MAVLINK_MAX_PAYLOAD_LEN 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. 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},}}) 360 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 361 char *buf = (char *)msgbuf; 362 ${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); 364 ${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); 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); 368 mavlink_${name_lower}_t *packet = (mavlink_${name_lower}_t *)msgbuf; 369 ${{scalar_fields: packet->${name} = ${putname}; 371 ${{array_fields: mav_array_memcpy(packet->${name}, ${name}, sizeof(${type})*${array_length}); 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); 380 // MESSAGE ${name} UNPACKING 384 * @brief Get field ${name} from ${name_lower} message 386 * @return ${units} ${description} 388 static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg}) 390 return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset}); 395 * @brief Decode a ${name_lower} message into a struct 397 * @param msg The message to decode 398 * @param ${name_lower} C-struct to decode the message contents into 400 static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower}) 402 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 403 ${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right}); 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); 416 '''generate testsuite.h per XML file''' 417 f = open(os.path.join(directory,
"testsuite.h"), mode=
'w')
420 * @brief MAVLink comm protocol testsuite generated from ${basename}.xml 421 * @see http://qgroundcontrol.org/mavlink/ 424 #ifndef ${basename_upper}_TESTSUITE_H 425 #define ${basename_upper}_TESTSUITE_H 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); 435 static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg); 437 static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 439 ${{include_list: mavlink_test_${base}(system_id, component_id, last_msg); 441 mavlink_test_${basename}(system_id, component_id, last_msg); 445 ${{include_list:#include "../${base}/testsuite.h" 449 static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 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) { 457 mavlink_message_t msg; 458 uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 460 mavlink_${name_lower}_t packet_in = { 461 ${{ordered_fields:${c_test_value},}} 463 mavlink_${name_lower}_t packet1, packet2; 464 memset(&packet1, 0, sizeof(packet1)); 465 ${{scalar_fields:packet1.${name} = packet_in.${name}; 467 ${{array_fields:mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length}); 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); 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); 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); 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); 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]); 495 mavlink_msg_${name_lower}_decode(last_msg, &packet2); 496 MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 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); 505 static void mavlink_test_${basename}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 507 ${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg); 513 #endif // __cplusplus 514 #endif // ${basename_upper}_TESTSUITE_H 520 '''copy the fixed protocol headers to the target directory''' 521 import shutil, filecmp
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' ]
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)):
536 shutil.copy(src, dest)
543 '''generate headers for one XML file''' 545 directory = os.path.join(basename, xml.basename)
547 print(
"Generating C implementation in directory %s" % directory)
548 mavparse.mkdir_p(directory)
550 if xml.little_endian:
551 xml.mavlink_endian =
"MAVLINK_LITTLE_ENDIAN" 553 xml.mavlink_endian =
"MAVLINK_BIG_ENDIAN" 556 xml.crc_extra_define =
"1" 558 xml.crc_extra_define =
"0" 560 if xml.command_24bit:
561 xml.command_24bit_define =
"1" 563 xml.command_24bit_define =
"0" 566 xml.aligned_fields_define =
"1" 568 xml.aligned_fields_define =
"0" 571 xml.include_list = []
572 for i
in xml.include:
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]
585 xml.message_crcs_array =
'' 586 if xml.command_24bit:
588 for msgid
in sorted(xml.message_crcs.keys()):
589 xml.message_crcs_array +=
'{%u, %u, %u, %u, %u, %u, %u}, ' % (msgid,
590 xml.message_crcs[msgid],
591 xml.message_min_lengths[msgid],
592 xml.message_lengths[msgid],
593 xml.message_flags[msgid],
594 xml.message_target_system_ofs[msgid],
595 xml.message_target_component_ofs[msgid])
597 for msgid
in range(256):
598 crc = xml.message_crcs.get(msgid, 0)
599 xml.message_crcs_array +=
'%u, ' % crc
600 xml.message_crcs_array = xml.message_crcs_array[:-2]
603 xml.message_info_array =
'' 604 if xml.command_24bit:
606 for msgid
in sorted(xml.message_names.keys()):
607 name = xml.message_names[msgid]
608 xml.message_info_array +=
'MAVLINK_MESSAGE_INFO_%s, ' % name
610 for msgid
in range(256):
611 name = xml.message_names.get(msgid,
None)
613 xml.message_info_array +=
'MAVLINK_MESSAGE_INFO_%s, ' % name
618 xml.message_info_array +=
'{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, ' 619 xml.message_info_array = xml.message_info_array[:-2]
622 xml.message_name_array =
'' 624 for msgid, name
in sorted(iteritems(xml.message_names), key=
lambda k_v: (k_v[1], k_v[0])):
625 xml.message_name_array +=
'{ "%s", %u }, ' % (name, msgid)
626 xml.message_name_array = xml.message_name_array[:-2]
629 for m
in xml.message:
632 m.crc_extra_arg =
", %s" % m.crc_extra
636 if f.print_format
is None:
637 f.c_print_format =
'NULL' 639 f.c_print_format =
'"%s"' % f.print_format
640 if f.array_length != 0:
641 f.array_suffix =
'[%u]' % f.array_length
643 f.array_tag =
'_array' 644 f.array_arg =
', %u' % f.array_length
645 f.array_return_arg =
'%s, %u, ' % (f.name, f.array_length)
646 f.array_const =
'const ' 648 f.decode_right =
', %s->%s' % (m.name_lower, f.name)
649 f.return_type =
'uint16_t' 650 f.get_arg =
', %s *%s' % (f.type, f.name)
652 f.c_test_value =
'"%s"' % f.test_value
655 for v
in f.test_value:
656 test_strings.append(
str(v))
657 f.c_test_value =
'{ %s }' %
', '.join(test_strings)
663 f.array_return_arg =
'' 665 f.decode_left =
"%s->%s = " % (m.name_lower, f.name)
668 f.return_type = f.type
670 f.c_test_value =
"'%s'" % f.test_value
671 elif f.type ==
'uint64_t':
672 f.c_test_value =
"%sULL" % f.test_value
673 elif f.type ==
'int64_t':
674 f.c_test_value =
"%sLL" % f.test_value
676 f.c_test_value = f.test_value
679 for m
in xml.message:
683 for f
in m.ordered_fields:
684 if f.array_length != 0:
685 m.array_fields.append(f)
687 m.scalar_fields.append(f)
690 m.arg_fields.append(f)
693 f.putname = f.const_value
698 for m
in xml.message:
704 '''generate complete MAVLink C implemenation''' 706 for idx
in range(len(xml_list)):
def generate_main_h(directory, xml)
def generate_one(basename, xml)
def generate_mavlink_h(directory, xml)
def copy_fixed_headers(directory, xml)
def generate_message_h(directory, m)
def generate_version_h(directory, xml)
def generate_testsuite_h(directory, xml)
def generate(basename, xml_list)