mavgen_c.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003 parse a MAVLink protocol XML file and generate a C implementation
00004 
00005 Copyright Andrew Tridgell 2011
00006 Released under GNU GPL version 3 or later
00007 '''
00008 
00009 import sys, textwrap, os, time
00010 from . import mavparse, mavtemplate
00011 
00012 t = mavtemplate.MAVTemplate()
00013 
00014 def generate_version_h(directory, xml):
00015     '''generate version.h'''
00016     f = open(os.path.join(directory, "version.h"), mode='w')
00017     t.write(f,'''
00018 /** @file
00019  *      @brief MAVLink comm protocol built from ${basename}.xml
00020  *      @see http://mavlink.org
00021  */
00022 #ifndef MAVLINK_VERSION_H
00023 #define MAVLINK_VERSION_H
00024 
00025 #define MAVLINK_BUILD_DATE "${parse_time}"
00026 #define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}"
00027 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload}
00028  
00029 #endif // MAVLINK_VERSION_H
00030 ''', xml)
00031     f.close()
00032 
00033 def generate_mavlink_h(directory, xml):
00034     '''generate mavlink.h'''
00035     f = open(os.path.join(directory, "mavlink.h"), mode='w')
00036     t.write(f,'''
00037 /** @file
00038  *      @brief MAVLink comm protocol built from ${basename}.xml
00039  *      @see http://mavlink.org
00040  */
00041 #ifndef MAVLINK_H
00042 #define MAVLINK_H
00043 
00044 #ifndef MAVLINK_STX
00045 #define MAVLINK_STX ${protocol_marker}
00046 #endif
00047 
00048 #ifndef MAVLINK_ENDIAN
00049 #define MAVLINK_ENDIAN ${mavlink_endian}
00050 #endif
00051 
00052 #ifndef MAVLINK_ALIGNED_FIELDS
00053 #define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define}
00054 #endif
00055 
00056 #ifndef MAVLINK_CRC_EXTRA
00057 #define MAVLINK_CRC_EXTRA ${crc_extra_define}
00058 #endif
00059 
00060 #ifndef MAVLINK_COMMAND_24BIT
00061 #define MAVLINK_COMMAND_24BIT ${command_24bit_define}
00062 #endif
00063 
00064 #ifndef MAVLINK_PACKED
00065 #define MAVLINK_PACKED __attribute__((__packed__))
00066 #endif
00067 
00068 #include "version.h"
00069 #include "${basename}.h"
00070 
00071 #endif // MAVLINK_H
00072 ''', xml)
00073     f.close()
00074 
00075 def generate_main_h(directory, xml):
00076     '''generate main header per XML file'''
00077     f = open(os.path.join(directory, xml.basename + ".h"), mode='w')
00078     t.write(f, '''
00079 /** @file
00080  *      @brief MAVLink comm protocol generated from ${basename}.xml
00081  *      @see http://mavlink.org
00082  */
00083 #ifndef MAVLINK_${basename_upper}_H
00084 #define MAVLINK_${basename_upper}_H
00085 
00086 #ifndef MAVLINK_H
00087     #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.
00088 #endif
00089 
00090 #ifdef __cplusplus
00091 extern "C" {
00092 #endif
00093 
00094 // MESSAGE LENGTHS AND CRCS
00095 
00096 #ifndef MAVLINK_MESSAGE_LENGTHS
00097 #define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}}
00098 #endif
00099 
00100 #ifndef MAVLINK_MESSAGE_CRCS
00101 #define MAVLINK_MESSAGE_CRCS {${message_crcs_array}}
00102 #endif
00103 
00104 #ifndef MAVLINK_MESSAGE_INFO
00105 #define MAVLINK_MESSAGE_INFO {${message_info_array}}
00106 #endif
00107 
00108 #include "../protocol.h"
00109 
00110 #define MAVLINK_ENABLED_${basename_upper}
00111 
00112 // ENUM DEFINITIONS
00113 
00114 ${{enum:
00115 /** @brief ${description} */
00116 #ifndef HAVE_ENUM_${name}
00117 #define HAVE_ENUM_${name}
00118 typedef enum ${name}
00119 {
00120 ${{entry:       ${name}=${value}, /* ${description} |${{param:${description}| }} */
00121 }}
00122 } ${name};
00123 #endif
00124 }}
00125 
00126 // MAVLINK VERSION
00127 
00128 #ifndef MAVLINK_VERSION
00129 #define MAVLINK_VERSION ${version}
00130 #endif
00131 
00132 #if (MAVLINK_VERSION == 0)
00133 #undef MAVLINK_VERSION
00134 #define MAVLINK_VERSION ${version}
00135 #endif
00136 
00137 // MESSAGE DEFINITIONS
00138 ${{message:#include "./mavlink_msg_${name_lower}.h"
00139 }}
00140 
00141 // base include
00142 ${{include_list:#include "../${base}/${base}.h"
00143 }}
00144 
00145 #if MAVLINK_COMMAND_24BIT
00146 #include "../mavlink_get_info.h"
00147 #endif
00148 
00149 #ifdef __cplusplus
00150 }
00151 #endif // __cplusplus
00152 #endif // MAVLINK_${basename_upper}_H
00153 ''', xml)
00154 
00155     f.close()
00156              
00157 
00158 def generate_message_h(directory, m):
00159     '''generate per-message header for a XML file'''
00160     f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w')
00161     t.write(f, '''
00162 // MESSAGE ${name} PACKING
00163 
00164 #define MAVLINK_MSG_ID_${name} ${id}
00165 
00166 typedef struct MAVLINK_PACKED __mavlink_${name_lower}_t
00167 {
00168 ${{ordered_fields: ${type} ${name}${array_suffix}; /*< ${description}*/
00169 }}
00170 } mavlink_${name_lower}_t;
00171 
00172 #define MAVLINK_MSG_ID_${name}_LEN ${wire_length}
00173 #define MAVLINK_MSG_ID_${name}_MIN_LEN ${wire_min_length}
00174 #define MAVLINK_MSG_ID_${id}_LEN ${wire_length}
00175 #define MAVLINK_MSG_ID_${id}_MIN_LEN ${wire_min_length}
00176 
00177 #define MAVLINK_MSG_ID_${name}_CRC ${crc_extra}
00178 #define MAVLINK_MSG_ID_${id}_CRC ${crc_extra}
00179 
00180 ${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length}
00181 }}
00182 
00183 #if MAVLINK_COMMAND_24BIT
00184 #define MAVLINK_MESSAGE_INFO_${name} { \\
00185         ${id}, \\
00186         "${name}", \\
00187         ${num_fields}, \\
00188         { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
00189         }} } \\
00190 }
00191 #else
00192 #define MAVLINK_MESSAGE_INFO_${name} { \\
00193         "${name}", \\
00194         ${num_fields}, \\
00195         { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
00196         }} } \\
00197 }
00198 #endif
00199 
00200 /**
00201  * @brief Pack a ${name_lower} message
00202  * @param system_id ID of this system
00203  * @param component_id ID of this component (e.g. 200 for IMU)
00204  * @param msg The MAVLink message to compress the data into
00205  *
00206 ${{arg_fields: * @param ${name} ${description}
00207 }}
00208  * @return length of the message in bytes (excluding serial stream start sign)
00209  */
00210 static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00211                                                       ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
00212 {
00213 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00214         char buf[MAVLINK_MSG_ID_${name}_LEN];
00215 ${{scalar_fields:       _mav_put_${type}(buf, ${wire_offset}, ${putname});
00216 }}
00217 ${{array_fields:        _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
00218 }}
00219         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN);
00220 #else
00221         mavlink_${name_lower}_t packet;
00222 ${{scalar_fields:       packet.${name} = ${putname};
00223 }}
00224 ${{array_fields:        mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
00225 }}
00226         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN);
00227 #endif
00228 
00229         msg->msgid = MAVLINK_MSG_ID_${name};
00230     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);
00231 }
00232 
00233 /**
00234  * @brief Pack a ${name_lower} message on a channel
00235  * @param system_id ID of this system
00236  * @param component_id ID of this component (e.g. 200 for IMU)
00237  * @param chan The MAVLink channel this message will be sent over
00238  * @param msg The MAVLink message to compress the data into
00239 ${{arg_fields: * @param ${name} ${description}
00240 }}
00241  * @return length of the message in bytes (excluding serial stream start sign)
00242  */
00243 static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00244                                                            mavlink_message_t* msg,
00245                                                            ${{arg_fields:${array_const}${type} ${array_prefix}${name},}})
00246 {
00247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00248         char buf[MAVLINK_MSG_ID_${name}_LEN];
00249 ${{scalar_fields:       _mav_put_${type}(buf, ${wire_offset}, ${putname});
00250 }}
00251 ${{array_fields:        _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
00252 }}
00253         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_${name}_LEN);
00254 #else
00255         mavlink_${name_lower}_t packet;
00256 ${{scalar_fields:       packet.${name} = ${putname};
00257 }}
00258 ${{array_fields:        mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
00259 }}
00260         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_${name}_LEN);
00261 #endif
00262 
00263         msg->msgid = MAVLINK_MSG_ID_${name};
00264     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);
00265 }
00266 
00267 /**
00268  * @brief Encode a ${name_lower} struct
00269  *
00270  * @param system_id ID of this system
00271  * @param component_id ID of this component (e.g. 200 for IMU)
00272  * @param msg The MAVLink message to compress the data into
00273  * @param ${name_lower} C-struct to read the message contents from
00274  */
00275 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})
00276 {
00277         return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}});
00278 }
00279 
00280 /**
00281  * @brief Encode a ${name_lower} struct on a channel
00282  *
00283  * @param system_id ID of this system
00284  * @param component_id ID of this component (e.g. 200 for IMU)
00285  * @param chan The MAVLink channel this message will be sent over
00286  * @param msg The MAVLink message to compress the data into
00287  * @param ${name_lower} C-struct to read the message contents from
00288  */
00289 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})
00290 {
00291         return mavlink_msg_${name_lower}_pack_chan(system_id, component_id, chan, msg,${{arg_fields: ${name_lower}->${name},}});
00292 }
00293 
00294 /**
00295  * @brief Send a ${name_lower} message
00296  * @param chan MAVLink channel to send the message
00297  *
00298 ${{arg_fields: * @param ${name} ${description}
00299 }}
00300  */
00301 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00302 
00303 static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
00304 {
00305 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00306         char buf[MAVLINK_MSG_ID_${name}_LEN];
00307 ${{scalar_fields:       _mav_put_${type}(buf, ${wire_offset}, ${putname});
00308 }}
00309 ${{array_fields:        _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
00310 }}
00311     _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);
00312 #else
00313         mavlink_${name_lower}_t packet;
00314 ${{scalar_fields:       packet.${name} = ${putname};
00315 }}
00316 ${{array_fields:        mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
00317 }}
00318     _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);
00319 #endif
00320 }
00321 
00322 /**
00323  * @brief Send a ${name_lower} message
00324  * @param chan MAVLink channel to send the message
00325  * @param struct The MAVLink struct to serialize
00326  */
00327 static inline void mavlink_msg_${name_lower}_send_struct(mavlink_channel_t chan, const mavlink_${name_lower}_t* ${name_lower})
00328 {
00329 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00330     mavlink_msg_${name_lower}_send(chan,${{arg_fields: ${name_lower}->${name},}});
00331 #else
00332     _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);
00333 #endif
00334 }
00335 
00336 #if MAVLINK_MSG_ID_${name}_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00337 /*
00338   This varient of _send() can be used to save stack space by re-using
00339   memory from the receive buffer.  The caller provides a
00340   mavlink_message_t which is the size of a full mavlink message. This
00341   is usually the receive buffer for the channel, and allows a reply to an
00342   incoming message with minimum stack space usage.
00343  */
00344 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},}})
00345 {
00346 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00347         char *buf = (char *)msgbuf;
00348 ${{scalar_fields:       _mav_put_${type}(buf, ${wire_offset}, ${putname});
00349 }}
00350 ${{array_fields:        _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
00351 }}
00352     _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);
00353 #else
00354         mavlink_${name_lower}_t *packet = (mavlink_${name_lower}_t *)msgbuf;
00355 ${{scalar_fields:       packet->${name} = ${putname};
00356 }}
00357 ${{array_fields:        mav_array_memcpy(packet->${name}, ${name}, sizeof(${type})*${array_length});
00358 }}
00359     _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);
00360 #endif
00361 }
00362 #endif
00363 
00364 #endif
00365 
00366 // MESSAGE ${name} UNPACKING
00367 
00368 ${{fields:
00369 /**
00370  * @brief Get field ${name} from ${name_lower} message
00371  *
00372  * @return ${description}
00373  */
00374 static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg})
00375 {
00376         return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset});
00377 }
00378 }}
00379 
00380 /**
00381  * @brief Decode a ${name_lower} message into a struct
00382  *
00383  * @param msg The message to decode
00384  * @param ${name_lower} C-struct to decode the message contents into
00385  */
00386 static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower})
00387 {
00388 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00389 ${{ordered_fields:      ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right});
00390 }}
00391 #else
00392         uint8_t len = msg->len < MAVLINK_MSG_ID_${name}_LEN? msg->len : MAVLINK_MSG_ID_${name}_LEN;
00393         memset(${name_lower}, 0, MAVLINK_MSG_ID_${name}_LEN);
00394         memcpy(${name_lower}, _MAV_PAYLOAD(msg), len);
00395 #endif
00396 }
00397 ''', m)
00398     f.close()
00399 
00400 
00401 def generate_testsuite_h(directory, xml):
00402     '''generate testsuite.h per XML file'''
00403     f = open(os.path.join(directory, "testsuite.h"), mode='w')
00404     t.write(f, '''
00405 /** @file
00406  *      @brief MAVLink comm protocol testsuite generated from ${basename}.xml
00407  *      @see http://qgroundcontrol.org/mavlink/
00408  */
00409 #ifndef ${basename_upper}_TESTSUITE_H
00410 #define ${basename_upper}_TESTSUITE_H
00411 
00412 #ifdef __cplusplus
00413 extern "C" {
00414 #endif
00415 
00416 #ifndef MAVLINK_TEST_ALL
00417 #define MAVLINK_TEST_ALL
00418 ${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg);
00419 }}
00420 static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg);
00421 
00422 static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
00423 {
00424 ${{include_list:        mavlink_test_${base}(system_id, component_id, last_msg);
00425 }}
00426         mavlink_test_${basename}(system_id, component_id, last_msg);
00427 }
00428 #endif
00429 
00430 ${{include_list:#include "../${base}/testsuite.h"
00431 }}
00432 
00433 ${{message:
00434 static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
00435 {
00436 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
00437         mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
00438         if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_${name} >= 256) {
00439                 return;
00440         }
00441 #endif
00442         mavlink_message_t msg;
00443         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
00444         uint16_t i;
00445         mavlink_${name_lower}_t packet_in = {
00446                 ${{ordered_fields:${c_test_value},}}
00447     };
00448         mavlink_${name_lower}_t packet1, packet2;
00449         memset(&packet1, 0, sizeof(packet1));
00450         ${{scalar_fields:packet1.${name} = packet_in.${name};
00451         }}
00452         ${{array_fields:mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length});
00453         }}
00454 
00455         memset(&packet2, 0, sizeof(packet2));
00456         mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1);
00457         mavlink_msg_${name_lower}_decode(&msg, &packet2);
00458         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
00459 
00460         memset(&packet2, 0, sizeof(packet2));
00461         mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }});
00462         mavlink_msg_${name_lower}_decode(&msg, &packet2);
00463         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
00464 
00465         memset(&packet2, 0, sizeof(packet2));
00466         mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }});
00467         mavlink_msg_${name_lower}_decode(&msg, &packet2);
00468         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
00469 
00470         memset(&packet2, 0, sizeof(packet2));
00471         mavlink_msg_to_send_buffer(buffer, &msg);
00472         for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
00473                 comm_send_ch(MAVLINK_COMM_0, buffer[i]);
00474         }
00475         mavlink_msg_${name_lower}_decode(last_msg, &packet2);
00476         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
00477         
00478         memset(&packet2, 0, sizeof(packet2));
00479         mavlink_msg_${name_lower}_send(MAVLINK_COMM_1 ${{arg_fields:, packet1.${name} }});
00480         mavlink_msg_${name_lower}_decode(last_msg, &packet2);
00481         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
00482 }
00483 }}
00484 
00485 static void mavlink_test_${basename}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
00486 {
00487 ${{message:     mavlink_test_${name_lower}(system_id, component_id, last_msg);
00488 }}
00489 }
00490 
00491 #ifdef __cplusplus
00492 }
00493 #endif // __cplusplus
00494 #endif // ${basename_upper}_TESTSUITE_H
00495 ''', xml)
00496 
00497     f.close()
00498 
00499 def copy_fixed_headers(directory, xml):
00500     '''copy the fixed protocol headers to the target directory'''
00501     import shutil, filecmp
00502     hlist = {
00503         "0.9": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h' ],
00504         "1.0": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_conversions.h' ],
00505         "2.0": [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_conversions.h',
00506                  'mavlink_get_info.h', 'mavlink_sha256.h' ]
00507         }
00508     basepath = os.path.dirname(os.path.realpath(__file__))
00509     srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version)
00510     print("Copying fixed headers for protocol %s to %s" % (xml.wire_protocol_version, directory))
00511     for h in hlist[xml.wire_protocol_version]:
00512         src = os.path.realpath(os.path.join(srcpath, h))
00513         dest = os.path.realpath(os.path.join(directory, h))
00514         if src == dest or (os.path.exists(dest) and filecmp.cmp(src, dest)):
00515             continue
00516         shutil.copy(src, dest)
00517 
00518 class mav_include(object):
00519     def __init__(self, base):
00520         self.base = base
00521 
00522 def generate_one(basename, xml):
00523     '''generate headers for one XML file'''
00524 
00525     directory = os.path.join(basename, xml.basename)
00526 
00527     print("Generating C implementation in directory %s" % directory)
00528     mavparse.mkdir_p(directory)
00529 
00530     if xml.little_endian:
00531         xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
00532     else:
00533         xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
00534 
00535     if xml.crc_extra:
00536         xml.crc_extra_define = "1"
00537     else:
00538         xml.crc_extra_define = "0"
00539 
00540     if xml.command_24bit:
00541         xml.command_24bit_define = "1"
00542     else:
00543         xml.command_24bit_define = "0"
00544 
00545     if xml.sort_fields:
00546         xml.aligned_fields_define = "1"
00547     else:
00548         xml.aligned_fields_define = "0"
00549 
00550     # work out the included headers
00551     xml.include_list = []
00552     for i in xml.include:
00553         base = i[:-4]
00554         xml.include_list.append(mav_include(base))
00555 
00556     # form message lengths array
00557     xml.message_lengths_array = ''
00558     if not xml.command_24bit:
00559         for msgid in range(256):
00560             mlen = xml.message_min_lengths.get(msgid, 0)
00561             xml.message_lengths_array += '%u, ' % mlen
00562         xml.message_lengths_array = xml.message_lengths_array[:-2]
00563 
00564     # and message CRCs array
00565     xml.message_crcs_array = ''
00566     if xml.command_24bit:
00567         # we sort with primary key msgid
00568         for msgid in sorted(xml.message_crcs.keys()):
00569             xml.message_crcs_array += '{%u, %u, %u, %u, %u, %u}, ' % (msgid,
00570                                                                       xml.message_crcs[msgid],
00571                                                                       xml.message_min_lengths[msgid],
00572                                                                       xml.message_flags[msgid],
00573                                                                       xml.message_target_system_ofs[msgid],
00574                                                                       xml.message_target_component_ofs[msgid])
00575     else:
00576         for msgid in range(256):
00577             crc = xml.message_crcs.get(msgid, 0)
00578             xml.message_crcs_array += '%u, ' % crc
00579     xml.message_crcs_array = xml.message_crcs_array[:-2]
00580 
00581     # form message info array
00582     xml.message_info_array = ''
00583     if xml.command_24bit:
00584         # we sort with primary key msgid
00585         for msgid in sorted(xml.message_names.keys()):
00586             name = xml.message_names[msgid]
00587             xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
00588     else:
00589         for msgid in range(256):
00590             name = xml.message_names.get(msgid, None)
00591             if name is not None:
00592                 xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
00593             else:
00594                 # Several C compilers don't accept {NULL} for
00595                 # multi-dimensional arrays and structs
00596                 # feed the compiler a "filled" empty message
00597                 xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
00598     xml.message_info_array = xml.message_info_array[:-2]
00599 
00600     # add some extra field attributes for convenience with arrays
00601     for m in xml.message:
00602         m.msg_name = m.name
00603         if xml.crc_extra:
00604             m.crc_extra_arg = ", %s" % m.crc_extra
00605         else:
00606             m.crc_extra_arg = ""
00607         for f in m.fields:
00608             if f.print_format is None:
00609                 f.c_print_format = 'NULL'
00610             else:
00611                 f.c_print_format = '"%s"' % f.print_format
00612             if f.array_length != 0:
00613                 f.array_suffix = '[%u]' % f.array_length
00614                 f.array_prefix = '*'
00615                 f.array_tag = '_array'
00616                 f.array_arg = ', %u' % f.array_length
00617                 f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
00618                 f.array_const = 'const '
00619                 f.decode_left = ''
00620                 f.decode_right = ', %s->%s' % (m.name_lower, f.name)
00621                 f.return_type = 'uint16_t'
00622                 f.get_arg = ', %s *%s' % (f.type, f.name)
00623                 if f.type == 'char':
00624                     f.c_test_value = '"%s"' % f.test_value
00625                 else:
00626                     test_strings = []
00627                     for v in f.test_value:
00628                         test_strings.append(str(v))
00629                     f.c_test_value = '{ %s }' % ', '.join(test_strings)
00630             else:
00631                 f.array_suffix = ''
00632                 f.array_prefix = ''
00633                 f.array_tag = ''
00634                 f.array_arg = ''
00635                 f.array_return_arg = ''
00636                 f.array_const = ''
00637                 f.decode_left = "%s->%s = " % (m.name_lower, f.name)
00638                 f.decode_right = ''
00639                 f.get_arg = ''
00640                 f.return_type = f.type
00641                 if f.type == 'char':
00642                     f.c_test_value = "'%s'" % f.test_value
00643                 elif f.type == 'uint64_t':
00644                     f.c_test_value = "%sULL" % f.test_value                    
00645                 elif f.type == 'int64_t':
00646                     f.c_test_value = "%sLL" % f.test_value                    
00647                 else:
00648                     f.c_test_value = f.test_value
00649 
00650     # cope with uint8_t_mavlink_version
00651     for m in xml.message:
00652         m.arg_fields = []
00653         m.array_fields = []
00654         m.scalar_fields = []
00655         for f in m.ordered_fields:
00656             if f.array_length != 0:
00657                 m.array_fields.append(f)
00658             else:
00659                 m.scalar_fields.append(f)
00660         for f in m.fields:
00661             if not f.omit_arg:
00662                 m.arg_fields.append(f)
00663                 f.putname = f.name
00664             else:
00665                 f.putname = f.const_value
00666 
00667     generate_mavlink_h(directory, xml)
00668     generate_version_h(directory, xml)
00669     generate_main_h(directory, xml)
00670     for m in xml.message:
00671         generate_message_h(directory, m)
00672     generate_testsuite_h(directory, xml)
00673 
00674 
00675 def generate(basename, xml_list):
00676     '''generate complete MAVLink C implemenation'''
00677 
00678     for xml in xml_list:
00679         generate_one(basename, xml)
00680     copy_fixed_headers(basename, xml_list[0])


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57