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(MAVLINK_MSG_LENGTH);
00163         packet.sysid = 255;
00164         packet.compid = 190;
00165         packet.msgid = MAVLINK_MSG_ID_${name};
00166         ${{ordered_fields:      
00167         ${packField}
00168         }}
00169         return packet;
00170     }
00171 
00172     /**
00173     * Decode a ${name_lower} message into this class fields
00174     *
00175     * @param payload The message to decode
00176     */
00177     public void unpack(MAVLinkPayload payload) {
00178         payload.resetIndex();
00179         ${{ordered_fields:      
00180         ${unpackField}
00181         }}
00182     }
00183 
00184     /**
00185     * Constructor for a new message, just initializes the msgid
00186     */
00187     public msg_${name_lower}(){
00188         msgid = MAVLINK_MSG_ID_${name};
00189     }
00190 
00191     /**
00192     * Constructor for a new message, initializes the message with the payload
00193     * from a mavlink packet
00194     *
00195     */
00196     public msg_${name_lower}(MAVLinkPacket mavLinkPacket){
00197         this.sysid = mavLinkPacket.sysid;
00198         this.compid = mavLinkPacket.compid;
00199         this.msgid = MAVLINK_MSG_ID_${name};
00200         unpack(mavLinkPacket.payload);        
00201     }
00202 
00203     ${{ordered_fields: ${getText} }}
00204     /**
00205     * Returns a string with the MSG name and data
00206     */
00207     public String toString(){
00208         return "MAVLINK_MSG_ID_${name} -"+${{ordered_fields:" ${name}:"+${name}+}}"";
00209     }
00210 }
00211         ''' % path[len(path)-1], m)
00212     f.close()
00213 
00214 
00215 def generate_MAVLinkMessage(directory, xml_list):
00216     f = open(os.path.join(directory, "MAVLinkPacket.java"), mode='w')
00217     t.write(f, '''
00218 /* AUTO-GENERATED FILE.  DO NOT MODIFY.
00219  *
00220  * This class was automatically generated by the
00221  * java mavlink generator tool. It should not be modified by hand.
00222  */
00223         
00224 package com.MAVLink;
00225 
00226 import java.io.Serializable;
00227 import com.MAVLink.Messages.MAVLinkPayload;
00228 import com.MAVLink.Messages.MAVLinkMessage;
00229 import com.MAVLink.${basename}.CRC;
00230 import com.MAVLink.common.*;
00231 import com.MAVLink.${basename}.*;
00232 
00233 /**
00234 * Common interface for all MAVLink Messages
00235 * Packet Anatomy
00236 * This is the anatomy of one packet. It is inspired by the CAN and SAE AS-4 standards.
00237 
00238 * Byte Index  Content              Value       Explanation
00239 * 0            Packet start sign  v1.0: 0xFE   Indicates the start of a new packet.  (v0.9: 0x55)
00240 * 1            Payload length      0 - 255     Indicates length of the following payload.
00241 * 2            Packet sequence     0 - 255     Each component counts up his send sequence. Allows to detect packet loss
00242 * 3            System ID           1 - 255     ID of the SENDING system. Allows to differentiate different MAVs on the same network.
00243 * 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.
00244 * 5            Message ID          0 - 255     ID of the message - the id defines what the payload means and how it should be correctly decoded.
00245 * 6 to (n+6)   Payload             0 - 255     Data of the message, depends on the message id.
00246 * (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).
00247 
00248 * 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
00249 * The minimum packet length is 8 bytes for acknowledgement packets without payload
00250 * The maximum packet length is 263 bytes for full payload
00251 *
00252 */
00253 public class MAVLinkPacket implements Serializable {
00254     private static final long serialVersionUID = 2095947771227815314L;
00255 
00256     public static final int MAVLINK_STX = 254;
00257 
00258     /**
00259     * Message length. NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
00260     */
00261     public final int len;
00262 
00263     /**
00264     * Message sequence
00265     */
00266     public int seq;
00267 
00268     /**
00269     * ID of the SENDING system. Allows to differentiate different MAVs on the
00270     * same network.
00271     */
00272     public int sysid;
00273 
00274     /**
00275     * ID of the SENDING component. Allows to differentiate different components
00276     * of the same system, e.g. the IMU and the autopilot.
00277     */
00278     public int compid;
00279 
00280     /**
00281     * ID of the message - the id defines what the payload means and how it
00282     * should be correctly decoded.
00283     */
00284     public int msgid;
00285 
00286     /**
00287     * Data of the message, depends on the message id.
00288     */
00289     public MAVLinkPayload payload;
00290 
00291     /**
00292     * ITU X.25/SAE AS-4 hash, excluding packet start sign, so bytes 1..(n+6)
00293     * Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from
00294     * message fields. Protects the packet from decoding a different version of
00295     * the same packet but with different variables).
00296     */
00297     public CRC crc;
00298 
00299     public MAVLinkPacket(int payloadLength){
00300         len = payloadLength;
00301         payload = new MAVLinkPayload(payloadLength);
00302     }
00303 
00304     /**
00305     * Check if the size of the Payload is equal to the "len" byte
00306     */
00307     public boolean payloadIsFilled() {
00308         return payload.size() >= len;
00309     }
00310 
00311     /**
00312     * Update CRC for this packet.
00313     */
00314     public void generateCRC(){
00315         if(crc == null){
00316             crc = new CRC();
00317         }
00318         else{
00319             crc.start_checksum();
00320         }
00321         
00322         crc.update_checksum(len);
00323         crc.update_checksum(seq);
00324         crc.update_checksum(sysid);
00325         crc.update_checksum(compid);
00326         crc.update_checksum(msgid);
00327 
00328         payload.resetIndex();
00329 
00330         final int payloadSize = payload.size();
00331         for (int i = 0; i < payloadSize; i++) {
00332             crc.update_checksum(payload.getByte());
00333         }
00334         crc.finish_checksum(msgid);
00335     }
00336 
00337     /**
00338     * Encode this packet for transmission.
00339     *
00340     * @return Array with bytes to be transmitted
00341     */
00342     public byte[] encodePacket() {
00343         byte[] buffer = new byte[6 + len + 2];
00344         
00345         int i = 0;
00346         buffer[i++] = (byte) MAVLINK_STX;
00347         buffer[i++] = (byte) len;
00348         buffer[i++] = (byte) seq;
00349         buffer[i++] = (byte) sysid;
00350         buffer[i++] = (byte) compid;
00351         buffer[i++] = (byte) msgid;
00352 
00353         final int payloadSize = payload.size();
00354         for (int j = 0; j < payloadSize; j++) {
00355             buffer[i++] = payload.payload.get(j);
00356         }
00357 
00358         generateCRC();
00359         buffer[i++] = (byte) (crc.getLSB());
00360         buffer[i++] = (byte) (crc.getMSB());
00361         return buffer;
00362     }
00363 
00364     /**
00365     * Unpack the data in this packet and return a MAVLink message
00366     *
00367     * @return MAVLink message decoded from this packet
00368     */
00369     public MAVLinkMessage unpack() {
00370         switch (msgid) {
00371         ''', xml_list[0])
00372     for xml in xml_list:
00373         t.write(f, '''
00374             ${{message:     
00375             case msg_${name_lower}.MAVLINK_MSG_ID_${name}:
00376                 return  new msg_${name_lower}(this);
00377             }}
00378             ''',xml)
00379     f.write('''
00380             default:
00381                 return null;
00382         }
00383     }
00384 
00385 }
00386         
00387         ''')
00388     
00389     f.close()
00390 
00391 def copy_fixed_headers(directory, xml):
00392     '''copy the fixed protocol headers to the target directory'''
00393     import shutil
00394     hlist = [ 'Parser.java', 'Messages/MAVLinkMessage.java', 'Messages/MAVLinkPayload.java', 'Messages/MAVLinkStats.java' ]
00395     basepath = os.path.dirname(os.path.realpath(__file__))
00396     srcpath = os.path.join(basepath, 'java/lib')
00397     print("Copying fixed headers")
00398     for h in hlist:
00399         src = os.path.realpath(os.path.join(srcpath, h))
00400         dest = os.path.realpath(os.path.join(directory, h))
00401         if src == dest:
00402             continue
00403         destdir = os.path.realpath(os.path.join(directory, 'Messages'))
00404         try:
00405             os.makedirs(destdir)
00406         except:
00407             print("Not re-creating Messages directory")
00408         shutil.copy(src, dest)
00409 
00410 class mav_include(object):
00411     def __init__(self, base):
00412         self.base = base
00413 
00414 
00415 def mavfmt(field, typeInfo=False):
00416     '''work out the struct format for a type'''
00417     map = {
00418         'float'    : ('float', 'Float'),
00419         'double'   : ('double', 'Double'),
00420         'char'     : ('byte', 'Byte'),
00421         'int8_t'   : ('byte', 'Byte'),
00422         'uint8_t'  : ('short', 'UnsignedByte'),
00423         'uint8_t_mavlink_version'  : ('short', 'UnsignedByte'),
00424         'int16_t'  : ('short', 'Short'),
00425         'uint16_t' : ('int', 'UnsignedShort'),
00426         'int32_t'  : ('int', 'Int'),
00427         'uint32_t' : ('long', 'UnsignedInt'),
00428         'int64_t'  : ('long', 'Long'),
00429         'uint64_t' : ('long', 'UnsignedLong'),
00430     }
00431     
00432     if typeInfo:
00433         return map[field.type][1]
00434     else:
00435         return map[field.type][0]
00436 
00437 def generate_one(basename, xml):
00438     '''generate headers for one XML file'''
00439     
00440     directory = os.path.join(basename, xml.basename)
00441     
00442     print("Generating Java implementation in directory %s" % directory)
00443     mavparse.mkdir_p(directory)
00444     
00445     if xml.little_endian:
00446         xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
00447     else:
00448         xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
00449     
00450     if xml.crc_extra:
00451         xml.crc_extra_define = "1"
00452     else:
00453         xml.crc_extra_define = "0"
00454     
00455     if xml.sort_fields:
00456         xml.aligned_fields_define = "1"
00457     else:
00458         xml.aligned_fields_define = "0"
00459     
00460     # work out the included headers
00461     xml.include_list = []
00462     for i in xml.include:
00463         base = i[:-4]
00464         xml.include_list.append(mav_include(base))
00465     
00466     # form message lengths array
00467     xml.message_lengths_array = ''
00468     for mlen in xml.message_lengths:
00469         xml.message_lengths_array += '%u, ' % mlen
00470     xml.message_lengths_array = xml.message_lengths_array[:-2]
00471     
00472     
00473     
00474     # form message info array
00475     xml.message_info_array = ''
00476     for name in xml.message_names:
00477         if name is not None:
00478             xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
00479         else:
00480             # Several C compilers don't accept {NULL} for
00481             # multi-dimensional arrays and structs
00482             # feed the compiler a "filled" empty message
00483             xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
00484     xml.message_info_array = xml.message_info_array[:-2]
00485     
00486     # add some extra field attributes for convenience with arrays
00487     for m in xml.message:
00488         m.msg_name = m.name
00489         if xml.crc_extra:
00490             m.crc_extra_arg = ", %s" % m.crc_extra
00491         else:
00492             m.crc_extra_arg = ""
00493         for f in m.fields:
00494             if f.print_format is None:
00495                 f.c_print_format = 'NULL'
00496             else:
00497                 f.c_print_format = '"%s"' % f.print_format
00498             f.getText = ''
00499             if f.array_length != 0:
00500                 f.array_suffix = '[] = new %s[%u]' % (mavfmt(f),f.array_length)
00501                 f.array_prefix = '*'
00502                 f.array_tag = '_array'
00503                 f.array_arg = ', %u' % f.array_length
00504                 f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
00505                 f.array_const = 'const '
00506                 f.decode_left = ''
00507                 f.decode_right = 'm.%s' % (f.name)
00508                 
00509                 f.unpackField = ''' 
00510         for (int i = 0; i < this.%s.length; i++) {
00511             this.%s[i] = payload.get%s();
00512         }
00513                 ''' % (f.name, f.name, mavfmt(f, True) )
00514                 f.packField = '''
00515         for (int i = 0; i < %s.length; i++) {
00516             packet.payload.put%s(%s[i]);
00517         }
00518                     ''' % (f.name, mavfmt(f, True),f.name)
00519                 f.return_type = 'uint16_t'
00520                 f.get_arg = ', %s *%s' % (f.type, f.name)
00521                 if f.type == 'char':
00522                     f.c_test_value = '"%s"' % f.test_value
00523                     f.getText = '''
00524     /**
00525     * Sets the buffer of this message with a string, adds the necessary padding
00526     */
00527     public void set%s(String str) {
00528         int len = Math.min(str.length(), %d);
00529         for (int i=0; i<len; i++) {
00530             %s[i] = (byte) str.charAt(i);
00531         }
00532 
00533         for (int i=len; i<%d; i++) {            // padding for the rest of the buffer
00534             %s[i] = 0;
00535         }
00536     }
00537 
00538     /**
00539     * Gets the message, formated as a string
00540     */
00541     public String get%s() {
00542         String result = "";
00543         for (int i = 0; i < %d; i++) {
00544             if (%s[i] != 0)
00545                 result = result + (char) %s[i];
00546             else
00547                 break;
00548         }
00549         return result;
00550 
00551     }
00552                         ''' % (f.name.title(),f.array_length,f.name,f.array_length,f.name,f.name.title(),f.array_length,f.name,f.name)
00553                 else:
00554                     test_strings = []
00555                     for v in f.test_value:
00556                         test_strings.append(str(v))
00557                     f.c_test_value = '{ %s }' % ', '.join(test_strings)
00558             else:
00559                 f.array_suffix = ''
00560                 f.array_prefix = ''
00561                 f.array_tag = ''
00562                 f.array_arg = ''
00563                 f.array_return_arg = ''
00564                 f.array_const = ''
00565                 f.decode_left =  '%s' % (f.name)
00566                 f.decode_right = ''
00567                 f.unpackField = 'this.%s = payload.get%s();' % (f.name, mavfmt(f, True))
00568                 f.packField = 'packet.payload.put%s(%s);' % (mavfmt(f, True),f.name)                   
00569                 
00570                 
00571                 f.get_arg = ''
00572                 f.return_type = f.type
00573                 if f.type == 'char':
00574                     f.c_test_value = "'%s'" % f.test_value
00575                 elif f.type == 'uint64_t':
00576                     f.c_test_value = "%sULL" % f.test_value                    
00577                 elif f.type == 'int64_t':
00578                     f.c_test_value = "%sLL" % f.test_value                    
00579                 else:
00580                     f.c_test_value = f.test_value
00581     
00582     # cope with uint8_t_mavlink_version
00583     for m in xml.message:
00584         m.arg_fields = []
00585         m.array_fields = []
00586         m.scalar_fields = []
00587         for f in m.ordered_fields:
00588             if f.array_length != 0:
00589                 m.array_fields.append(f)
00590             else:
00591                 m.scalar_fields.append(f)
00592         for f in m.fields:
00593             if not f.omit_arg:
00594                 m.arg_fields.append(f)
00595                 f.putname = f.name
00596             else:
00597                 f.putname = f.const_value
00598     
00599     # fix types to java
00600     for m in xml.message:
00601         for f in m.ordered_fields:
00602             f.type = mavfmt(f)
00603     
00604     generate_CRC(directory, xml)
00605     
00606     for m in xml.message:
00607         generate_message_h(directory, m)
00608 
00609 
00610 def generate(basename, xml_list):
00611     '''generate complete MAVLink Java implemenation'''
00612     for xml in xml_list:
00613         generate_one(basename, xml)
00614         generate_enums(basename, xml)
00615         generate_MAVLinkMessage(basename, xml_list)
00616     copy_fixed_headers(basename, xml_list[0])


mavlink
Author(s): Lorenz Meier
autogenerated on Sun May 22 2016 04:05:43