mavgen_java.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003     Parse a MAVLink protocol XML file and generate a Java 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_enums(basename, xml):
00015     '''generate main header per XML file'''
00016     directory = os.path.join(basename, '''enums''')
00017     mavparse.mkdir_p(directory)
00018     for en in xml.enum:
00019         f = open(os.path.join(directory, en.name+".java"), mode='w')
00020         t.write(f, '''
00021 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00022  *
00023  * This class was automatically generated by the
00024  * java mavlink generator tool. It should not be modified by hand.
00025  */
00026 
00027 package com.MAVLink.enums;
00028 
00029 /** 
00030 * ${description}
00031 */
00032 public class ${name} {
00033 ${{entry:   public static final int ${name} = ${value}; /* ${description} |${{param:${description}| }} */
00034 }}
00035 }
00036             ''', en)
00037         f.close()
00038 
00039 
00040 
00041 def generate_CRC(directory, xml):
00042     # and message CRCs array
00043     xml.message_crcs_array = ''
00044     for crc in xml.message_crcs:
00045         xml.message_crcs_array += '%u, ' % crc
00046     xml.message_crcs_array = xml.message_crcs_array[:-2]
00047     
00048     f = open(os.path.join(directory, "CRC.java"), mode='w')
00049     t.write(f,'''
00050 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00051  *
00052  * This class was automatically generated by the
00053  * java mavlink generator tool. It should not be modified by hand.
00054  */
00055 
00056 package com.MAVLink.${basename};
00057 
00058 /**
00059 * X.25 CRC calculation for MAVlink messages. The checksum must be initialized,
00060 * updated with witch field of the message, and then finished with the message
00061 * id.
00062 *
00063 */
00064 public class CRC {
00065     private static final int[] MAVLINK_MESSAGE_CRCS = {${message_crcs_array}};
00066     private static final int CRC_INIT_VALUE = 0xffff;
00067     private int crcValue;
00068 
00069     /**
00070     * Accumulate the X.25 CRC by adding one char at a time.
00071     *
00072     * The checksum function adds the hash of one char at a time to the 16 bit
00073     * checksum (uint16_t).
00074     *
00075     * @param data
00076     *            new char to hash
00077     **/
00078     public  void update_checksum(int data) {
00079         data = data & 0xff; //cast because we want an unsigned type
00080         int tmp = data ^ (crcValue & 0xff);
00081         tmp ^= (tmp << 4) & 0xff;
00082         crcValue = ((crcValue >> 8) & 0xff) ^ (tmp << 8) ^ (tmp << 3) ^ ((tmp >> 4) & 0xf);
00083     }
00084 
00085     /**
00086     * Finish the CRC calculation of a message, by running the CRC with the
00087     * Magic Byte. This Magic byte has been defined in MAVlink v1.0.
00088     *
00089     * @param msgid
00090     *            The message id number
00091     */
00092     public void finish_checksum(int msgid) {
00093         update_checksum(MAVLINK_MESSAGE_CRCS[msgid]);
00094     }
00095 
00096     /**
00097     * Initialize the buffer for the X.25 CRC
00098     *
00099     */
00100     public void start_checksum() {
00101         crcValue = CRC_INIT_VALUE;
00102     }
00103 
00104     public int getMSB() {
00105         return ((crcValue >> 8) & 0xff);
00106     }
00107 
00108     public int getLSB() {
00109         return (crcValue & 0xff);
00110     }
00111 
00112     public CRC() {
00113         start_checksum();
00114     }
00115 
00116 }
00117         ''',xml)
00118     
00119     f.close()
00120 
00121 
00122 def generate_message_h(directory, m):
00123     '''generate per-message header for a XML file'''
00124     f = open(os.path.join(directory, 'msg_%s.java' % m.name_lower), mode='w')
00125 
00126     path=directory.split('/')
00127     t.write(f, '''
00128 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00129  *
00130  * This class was automatically generated by the
00131  * java mavlink generator tool. It should not be modified by hand.
00132  */
00133 
00134 // MESSAGE ${name} PACKING
00135 package com.MAVLink.%s;
00136 import com.MAVLink.MAVLinkPacket;
00137 import com.MAVLink.Messages.MAVLinkMessage;
00138 import com.MAVLink.Messages.MAVLinkPayload;
00139         
00140 /**
00141 * ${description}
00142 */
00143 public class msg_${name_lower} extends MAVLinkMessage{
00144 
00145     public static final int MAVLINK_MSG_ID_${name} = ${id};
00146     public static final int MAVLINK_MSG_LENGTH = ${wire_length};
00147     private static final long serialVersionUID = MAVLINK_MSG_ID_${name};
00148 
00149 
00150     ${{ordered_fields:  
00151     /**
00152     * ${description}
00153     */
00154     public ${type} ${name}${array_suffix};
00155     }}
00156 
00157     /**
00158     * Generates the payload for a mavlink message for a message of this type
00159     * @return
00160     */
00161     public MAVLinkPacket pack(){
00162         MAVLinkPacket packet = new MAVLinkPacket();
00163         packet.len = MAVLINK_MSG_LENGTH;
00164         packet.sysid = 255;
00165         packet.compid = 190;
00166         packet.msgid = MAVLINK_MSG_ID_${name};
00167         ${{ordered_fields:      
00168         ${packField}
00169         }}
00170         return packet;
00171     }
00172 
00173     /**
00174     * Decode a ${name_lower} message into this class fields
00175     *
00176     * @param payload The message to decode
00177     */
00178     public void unpack(MAVLinkPayload payload) {
00179         payload.resetIndex();
00180         ${{ordered_fields:      
00181         ${unpackField}
00182         }}
00183     }
00184 
00185     /**
00186     * Constructor for a new message, just initializes the msgid
00187     */
00188     public msg_${name_lower}(){
00189         msgid = MAVLINK_MSG_ID_${name};
00190     }
00191 
00192     /**
00193     * Constructor for a new message, initializes the message with the payload
00194     * from a mavlink packet
00195     *
00196     */
00197     public msg_${name_lower}(MAVLinkPacket mavLinkPacket){
00198         this.sysid = mavLinkPacket.sysid;
00199         this.compid = mavLinkPacket.compid;
00200         this.msgid = MAVLINK_MSG_ID_${name};
00201         unpack(mavLinkPacket.payload);        
00202     }
00203 
00204     ${{ordered_fields: ${getText} }}
00205     /**
00206     * Returns a string with the MSG name and data
00207     */
00208     public String toString(){
00209         return "MAVLINK_MSG_ID_${name} -"+${{ordered_fields:" ${name}:"+${name}+}}"";
00210     }
00211 }
00212         ''' % path[len(path)-1], m)
00213     f.close()
00214 
00215 
00216 def generate_MAVLinkMessage(directory, xml_list):
00217     f = open(os.path.join(directory, "MAVLinkPacket.java"), mode='w')
00218     f.write('''
00219 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00220  *
00221  * This class was automatically generated by the
00222  * java mavlink generator tool. It should not be modified by hand.
00223  */
00224         
00225 package com.MAVLink;
00226 
00227 import java.io.Serializable;
00228 import com.MAVLink.Messages.MAVLinkPayload;
00229 import com.MAVLink.Messages.MAVLinkMessage;
00230 import com.MAVLink.ardupilotmega.CRC;
00231 import com.MAVLink.common.*;
00232 import com.MAVLink.ardupilotmega.*;
00233 
00234 /**
00235 * Common interface for all MAVLink Messages
00236 * Packet Anatomy
00237 * This is the anatomy of one packet. It is inspired by the CAN and SAE AS-4 standards.
00238 
00239 * Byte Index  Content              Value       Explanation
00240 * 0            Packet start sign  v1.0: 0xFE   Indicates the start of a new packet.  (v0.9: 0x55)
00241 * 1            Payload length      0 - 255     Indicates length of the following payload.
00242 * 2            Packet sequence     0 - 255     Each component counts up his send sequence. Allows to detect packet loss
00243 * 3            System ID           1 - 255     ID of the SENDING system. Allows to differentiate different MAVs on the same network.
00244 * 4            Component ID        0 - 255     ID of the SENDING component. Allows to differentiate different components of the same system, e.g. the IMU and the autopilot.
00245 * 5            Message ID          0 - 255     ID of the message - the id defines what the payload means and how it should be correctly decoded.
00246 * 6 to (n+6)   Payload             0 - 255     Data of the message, depends on the message id.
00247 * (n+7)to(n+8) Checksum (low byte, high byte)  ITU X.25/SAE AS-4 hash, excluding packet start sign, so bytes 1..(n+6) Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from message fields. Protects the packet from decoding a different version of the same packet but with different variables).
00248 
00249 * The checksum is the same as used in ITU X.25 and SAE AS-4 standards (CRC-16-CCITT), documented in SAE AS5669A. Please see the MAVLink source code for a documented C-implementation of it. LINK TO CHECKSUM
00250 * The minimum packet length is 8 bytes for acknowledgement packets without payload
00251 * The maximum packet length is 263 bytes for full payload
00252 *
00253 */
00254 public class MAVLinkPacket implements Serializable {
00255     private static final long serialVersionUID = 2095947771227815314L;
00256 
00257     public static final int MAVLINK_STX = 254;
00258 
00259     /**
00260     * Message length. NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
00261     */
00262     public int len;
00263 
00264     /**
00265     * Message sequence
00266     */
00267     public int seq;
00268 
00269     /**
00270     * ID of the SENDING system. Allows to differentiate different MAVs on the
00271     * same network.
00272     */
00273     public int sysid;
00274 
00275     /**
00276     * ID of the SENDING component. Allows to differentiate different components
00277     * of the same system, e.g. the IMU and the autopilot.
00278     */
00279     public int compid;
00280 
00281     /**
00282     * ID of the message - the id defines what the payload means and how it
00283     * should be correctly decoded.
00284     */
00285     public int msgid;
00286 
00287     /**
00288     * Data of the message, depends on the message id.
00289     */
00290     public MAVLinkPayload payload;
00291 
00292     /**
00293     * ITU X.25/SAE AS-4 hash, excluding packet start sign, so bytes 1..(n+6)
00294     * Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from
00295     * message fields. Protects the packet from decoding a different version of
00296     * the same packet but with different variables).
00297     */
00298     public CRC crc;
00299 
00300     public MAVLinkPacket(){
00301         payload = new MAVLinkPayload();
00302     }
00303 
00304     /**
00305     * Check if the size of the Payload is equal to the "len" byte
00306     */
00307     public boolean payloadIsFilled() {
00308         if (payload.size() >= MAVLinkPayload.MAX_PAYLOAD_SIZE-1) {
00309             return true;
00310         }
00311         return (payload.size() == len);
00312     }
00313 
00314     /**
00315     * Update CRC for this packet.
00316     */
00317     public void generateCRC(){
00318         if(crc == null){
00319             crc = new CRC();
00320         }
00321         else{
00322             crc.start_checksum();
00323         }
00324         
00325         crc.update_checksum(len);
00326         crc.update_checksum(seq);
00327         crc.update_checksum(sysid);
00328         crc.update_checksum(compid);
00329         crc.update_checksum(msgid);
00330 
00331         payload.resetIndex();
00332         
00333         for (int i = 0; i < payload.size(); i++) {
00334             crc.update_checksum(payload.getByte());
00335         }
00336         crc.finish_checksum(msgid);
00337     }
00338 
00339     /**
00340     * Encode this packet for transmission.
00341     *
00342     * @return Array with bytes to be transmitted
00343     */
00344     public byte[] encodePacket() {
00345         byte[] buffer = new byte[6 + len + 2];
00346         
00347         int i = 0;
00348         buffer[i++] = (byte) MAVLINK_STX;
00349         buffer[i++] = (byte) len;
00350         buffer[i++] = (byte) seq;
00351         buffer[i++] = (byte) sysid;
00352         buffer[i++] = (byte) compid;
00353         buffer[i++] = (byte) msgid;
00354         
00355         for (int j = 0; j < payload.size(); j++) {
00356             buffer[i++] = payload.payload.get(j);
00357         }
00358 
00359         generateCRC();
00360         buffer[i++] = (byte) (crc.getLSB());
00361         buffer[i++] = (byte) (crc.getMSB());
00362         return buffer;
00363     }
00364 
00365     /**
00366     * Unpack the data in this packet and return a MAVLink message
00367     *
00368     * @return MAVLink message decoded from this packet
00369     */
00370     public MAVLinkMessage unpack() {
00371         switch (msgid) {
00372         ''')
00373     for xml in xml_list:
00374         t.write(f, '''
00375             ${{message:     
00376             case msg_${name_lower}.MAVLINK_MSG_ID_${name}:
00377                 return  new msg_${name_lower}(this);
00378             }}
00379             ''',xml)
00380     f.write('''
00381             default:
00382                 return null;
00383         }
00384     }
00385 
00386 }
00387         
00388         ''')
00389     
00390     f.close()
00391 
00392 def copy_fixed_headers(directory, xml):
00393     '''copy the fixed protocol headers to the target directory'''
00394     import shutil
00395     hlist = [ 'Parser.java', 'Messages/MAVLinkMessage.java', 'Messages/MAVLinkPayload.java', 'Messages/MAVLinkStats.java' ]
00396     basepath = os.path.dirname(os.path.realpath(__file__))
00397     srcpath = os.path.join(basepath, 'java/lib')
00398     print("Copying fixed headers")
00399     for h in hlist:
00400         src = os.path.realpath(os.path.join(srcpath, h))
00401         dest = os.path.realpath(os.path.join(directory, h))
00402         if src == dest:
00403             continue
00404         destdir = os.path.realpath(os.path.join(directory, 'Messages'))
00405         try:
00406             os.makedirs(destdir)
00407         except:
00408             print("Not re-creating Messages directory")
00409         shutil.copy(src, dest)
00410 
00411 class mav_include(object):
00412     def __init__(self, base):
00413         self.base = base
00414 
00415 
00416 def mavfmt(field, typeInfo=False):
00417     '''work out the struct format for a type'''
00418     map = {
00419         'float'    : ('float', 'Float'),
00420         'double'   : ('double', 'Double'),
00421         'char'     : ('byte', 'Byte'),
00422         'int8_t'   : ('byte', 'Byte'),
00423         'uint8_t'  : ('short', 'UnsignedByte'),
00424         'uint8_t_mavlink_version'  : ('short', 'UnsignedByte'),
00425         'int16_t'  : ('short', 'Short'),
00426         'uint16_t' : ('int', 'UnsignedShort'),
00427         'int32_t'  : ('int', 'Int'),
00428         'uint32_t' : ('long', 'UnsignedInt'),
00429         'int64_t'  : ('long', 'Long'),
00430         'uint64_t' : ('long', 'UnsignedLong'),
00431     }
00432     
00433     if typeInfo:
00434         return map[field.type][1]
00435     else:
00436         return map[field.type][0]
00437 
00438 def generate_one(basename, xml):
00439     '''generate headers for one XML file'''
00440     
00441     directory = os.path.join(basename, xml.basename)
00442     
00443     print("Generating Java implementation in directory %s" % directory)
00444     mavparse.mkdir_p(directory)
00445     
00446     if xml.little_endian:
00447         xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
00448     else:
00449         xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
00450     
00451     if xml.crc_extra:
00452         xml.crc_extra_define = "1"
00453     else:
00454         xml.crc_extra_define = "0"
00455     
00456     if xml.sort_fields:
00457         xml.aligned_fields_define = "1"
00458     else:
00459         xml.aligned_fields_define = "0"
00460     
00461     # work out the included headers
00462     xml.include_list = []
00463     for i in xml.include:
00464         base = i[:-4]
00465         xml.include_list.append(mav_include(base))
00466     
00467     # form message lengths array
00468     xml.message_lengths_array = ''
00469     for mlen in xml.message_lengths:
00470         xml.message_lengths_array += '%u, ' % mlen
00471     xml.message_lengths_array = xml.message_lengths_array[:-2]
00472     
00473     
00474     
00475     # form message info array
00476     xml.message_info_array = ''
00477     for name in xml.message_names:
00478         if name is not None:
00479             xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
00480         else:
00481             # Several C compilers don't accept {NULL} for
00482             # multi-dimensional arrays and structs
00483             # feed the compiler a "filled" empty message
00484             xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
00485     xml.message_info_array = xml.message_info_array[:-2]
00486     
00487     # add some extra field attributes for convenience with arrays
00488     for m in xml.message:
00489         m.msg_name = m.name
00490         if xml.crc_extra:
00491             m.crc_extra_arg = ", %s" % m.crc_extra
00492         else:
00493             m.crc_extra_arg = ""
00494         for f in m.fields:
00495             if f.print_format is None:
00496                 f.c_print_format = 'NULL'
00497             else:
00498                 f.c_print_format = '"%s"' % f.print_format
00499             f.getText = ''
00500             if f.array_length != 0:
00501                 f.array_suffix = '[] = new %s[%u]' % (mavfmt(f),f.array_length)
00502                 f.array_prefix = '*'
00503                 f.array_tag = '_array'
00504                 f.array_arg = ', %u' % f.array_length
00505                 f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
00506                 f.array_const = 'const '
00507                 f.decode_left = ''
00508                 f.decode_right = 'm.%s' % (f.name)
00509                 
00510                 f.unpackField = ''' 
00511         for (int i = 0; i < this.%s.length; i++) {
00512             this.%s[i] = payload.get%s();
00513         }
00514                 ''' % (f.name, f.name, mavfmt(f, True) )
00515                 f.packField = '''
00516         for (int i = 0; i < %s.length; i++) {
00517             packet.payload.put%s(%s[i]);
00518         }
00519                     ''' % (f.name, mavfmt(f, True),f.name)
00520                 f.return_type = 'uint16_t'
00521                 f.get_arg = ', %s *%s' % (f.type, f.name)
00522                 if f.type == 'char':
00523                     f.c_test_value = '"%s"' % f.test_value
00524                     f.getText = '''
00525     /**
00526     * Sets the buffer of this message with a string, adds the necessary padding
00527     */
00528     public void set%s(String str) {
00529         int len = Math.min(str.length(), %d);
00530         for (int i=0; i<len; i++) {
00531             %s[i] = (byte) str.charAt(i);
00532         }
00533 
00534         for (int i=len; i<%d; i++) {            // padding for the rest of the buffer
00535             %s[i] = 0;
00536         }
00537     }
00538 
00539     /**
00540     * Gets the message, formated as a string
00541     */
00542     public String get%s() {
00543         String result = "";
00544         for (int i = 0; i < %d; i++) {
00545             if (%s[i] != 0)
00546                 result = result + (char) %s[i];
00547             else
00548                 break;
00549         }
00550         return result;
00551 
00552     }
00553                         ''' % (f.name.title(),f.array_length,f.name,f.array_length,f.name,f.name.title(),f.array_length,f.name,f.name)
00554                 else:
00555                     test_strings = []
00556                     for v in f.test_value:
00557                         test_strings.append(str(v))
00558                     f.c_test_value = '{ %s }' % ', '.join(test_strings)
00559             else:
00560                 f.array_suffix = ''
00561                 f.array_prefix = ''
00562                 f.array_tag = ''
00563                 f.array_arg = ''
00564                 f.array_return_arg = ''
00565                 f.array_const = ''
00566                 f.decode_left =  '%s' % (f.name)
00567                 f.decode_right = ''
00568                 f.unpackField = 'this.%s = payload.get%s();' % (f.name, mavfmt(f, True))
00569                 f.packField = 'packet.payload.put%s(%s);' % (mavfmt(f, True),f.name)                   
00570                 
00571                 
00572                 f.get_arg = ''
00573                 f.return_type = f.type
00574                 if f.type == 'char':
00575                     f.c_test_value = "'%s'" % f.test_value
00576                 elif f.type == 'uint64_t':
00577                     f.c_test_value = "%sULL" % f.test_value                    
00578                 elif f.type == 'int64_t':
00579                     f.c_test_value = "%sLL" % f.test_value                    
00580                 else:
00581                     f.c_test_value = f.test_value
00582     
00583     # cope with uint8_t_mavlink_version
00584     for m in xml.message:
00585         m.arg_fields = []
00586         m.array_fields = []
00587         m.scalar_fields = []
00588         for f in m.ordered_fields:
00589             if f.array_length != 0:
00590                 m.array_fields.append(f)
00591             else:
00592                 m.scalar_fields.append(f)
00593         for f in m.fields:
00594             if not f.omit_arg:
00595                 m.arg_fields.append(f)
00596                 f.putname = f.name
00597             else:
00598                 f.putname = f.const_value
00599     
00600     # fix types to java
00601     for m in xml.message:
00602         for f in m.ordered_fields:
00603             f.type = mavfmt(f)
00604     
00605     generate_CRC(directory, xml)
00606     
00607     for m in xml.message:
00608         generate_message_h(directory, m)
00609 
00610 
00611 def generate(basename, xml_list):
00612     '''generate complete MAVLink Java implemenation'''
00613     for xml in xml_list:
00614         generate_one(basename, xml)
00615         generate_enums(basename, xml)
00616         generate_MAVLinkMessage(basename, xml_list)
00617     copy_fixed_headers(basename, xml_list[0])


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17