mavgen_java.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3  Parse a MAVLink protocol XML file and generate a Java implementation
4 
5  Copyright Andrew Tridgell 2011
6  Released under GNU GPL version 3 or later
7  '''
8 from __future__ import print_function
9 
10 from builtins import range
11 from builtins import object
12 
13 import os
14 from . import mavparse, mavtemplate
15 
17 
18 def generate_enums(basename, xml):
19  '''generate main header per XML file'''
20  directory = os.path.join(basename, '''enums''')
21  mavparse.mkdir_p(directory)
22  for en in xml.enum:
23  f = open(os.path.join(directory, en.name+".java"), mode='w')
24  t.write(f, '''
25 /* AUTO-GENERATED FILE. DO NOT MODIFY.
26  *
27  * This class was automatically generated by the
28  * java mavlink generator tool. It should not be modified by hand.
29  */
30 
31 package com.MAVLink.enums;
32 
33 /**
34 * ${description}
35 */
36 public class ${name} {
37 ${{entry: public static final int ${name} = ${value}; /* ${description} |${{param:${description}| }} */
38 }}
39 }
40  ''', en)
41  f.close()
42 
43 
44 
45 def generate_CRC(directory, xml):
46  # and message CRCs array
47  xml.message_crcs_array = ''
48  for msgid in range(256):
49  crc = xml.message_crcs.get(msgid, 0)
50  xml.message_crcs_array += '%u, ' % crc
51  xml.message_crcs_array = xml.message_crcs_array[:-2]
52 
53  f = open(os.path.join(directory, "CRC.java"), mode='w')
54  t.write(f,'''
55 /* AUTO-GENERATED FILE. DO NOT MODIFY.
56  *
57  * This class was automatically generated by the
58  * java mavlink generator tool. It should not be modified by hand.
59  */
60 
61 package com.MAVLink.${basename};
62 
63 /**
64 * X.25 CRC calculation for MAVlink messages. The checksum must be initialized,
65 * updated with witch field of the message, and then finished with the message
66 * id.
67 *
68 */
69 public class CRC {
70  private static final int[] MAVLINK_MESSAGE_CRCS = {${message_crcs_array}};
71  private static final int CRC_INIT_VALUE = 0xffff;
72  private int crcValue;
73 
74  /**
75  * Accumulate the X.25 CRC by adding one char at a time.
76  *
77  * The checksum function adds the hash of one char at a time to the 16 bit
78  * checksum (uint16_t).
79  *
80  * @param data
81  * new char to hash
82  **/
83  public void update_checksum(int data) {
84  data = data & 0xff; //cast because we want an unsigned type
85  int tmp = data ^ (crcValue & 0xff);
86  tmp ^= (tmp << 4) & 0xff;
87  crcValue = ((crcValue >> 8) & 0xff) ^ (tmp << 8) ^ (tmp << 3) ^ ((tmp >> 4) & 0xf);
88  }
89 
90  /**
91  * Finish the CRC calculation of a message, by running the CRC with the
92  * Magic Byte. This Magic byte has been defined in MAVlink v1.0.
93  *
94  * @param msgid
95  * The message id number
96  */
97  public void finish_checksum(int msgid) {
98  update_checksum(MAVLINK_MESSAGE_CRCS[msgid]);
99  }
100 
101  /**
102  * Initialize the buffer for the X.25 CRC
103  *
104  */
105  public void start_checksum() {
106  crcValue = CRC_INIT_VALUE;
107  }
108 
109  public int getMSB() {
110  return ((crcValue >> 8) & 0xff);
111  }
112 
113  public int getLSB() {
114  return (crcValue & 0xff);
115  }
116 
117  public CRC() {
118  start_checksum();
119  }
120 
121 }
122  ''',xml)
123 
124  f.close()
125 
126 
127 def generate_message_h(directory, m):
128  '''generate per-message header for a XML file'''
129  f = open(os.path.join(directory, 'msg_%s.java' % m.name_lower), mode='w')
130 
131  (path_head, path_tail) = os.path.split(directory)
132  if path_tail == "":
133  (path_head, path_tail) = os.path.split(path_head)
134  t.write(f, '''
135 /* AUTO-GENERATED FILE. DO NOT MODIFY.
136  *
137  * This class was automatically generated by the
138  * java mavlink generator tool. It should not be modified by hand.
139  */
140 
141 // MESSAGE ${name} PACKING
142 package com.MAVLink.%s;
143 import com.MAVLink.MAVLinkPacket;
144 import com.MAVLink.Messages.MAVLinkMessage;
145 import com.MAVLink.Messages.MAVLinkPayload;
146 
147 /**
148 * ${description}
149 */
150 public class msg_${name_lower} extends MAVLinkMessage{
151 
152  public static final int MAVLINK_MSG_ID_${name} = ${id};
153  public static final int MAVLINK_MSG_LENGTH = ${wire_length};
154  private static final long serialVersionUID = MAVLINK_MSG_ID_${name};
155 
156 
157  ${{ordered_fields:
158  /**
159  * ${description}
160  */
161  public ${type} ${name}${array_suffix};
162  }}
163 
164  /**
165  * Generates the payload for a mavlink message for a message of this type
166  * @return
167  */
168  public MAVLinkPacket pack(){
169  MAVLinkPacket packet = new MAVLinkPacket(MAVLINK_MSG_LENGTH);
170  packet.sysid = 255;
171  packet.compid = 190;
172  packet.msgid = MAVLINK_MSG_ID_${name};
173  ${{ordered_fields:
174  ${packField}
175  }}
176  return packet;
177  }
178 
179  /**
180  * Decode a ${name_lower} message into this class fields
181  *
182  * @param payload The message to decode
183  */
184  public void unpack(MAVLinkPayload payload) {
185  payload.resetIndex();
186  ${{ordered_fields:
187  ${unpackField}
188  }}
189  }
190 
191  /**
192  * Constructor for a new message, just initializes the msgid
193  */
194  public msg_${name_lower}(){
195  msgid = MAVLINK_MSG_ID_${name};
196  }
197 
198  /**
199  * Constructor for a new message, initializes the message with the payload
200  * from a mavlink packet
201  *
202  */
203  public msg_${name_lower}(MAVLinkPacket mavLinkPacket){
204  this.sysid = mavLinkPacket.sysid;
205  this.compid = mavLinkPacket.compid;
206  this.msgid = MAVLINK_MSG_ID_${name};
207  unpack(mavLinkPacket.payload);
208  }
209 
210  ${{ordered_fields: ${getText} }}
211  /**
212  * Returns a string with the MSG name and data
213  */
214  public String toString(){
215  return "MAVLINK_MSG_ID_${name} - sysid:"+sysid+" compid:"+compid+${{ordered_fields:" ${name}:"+${name}+}}"";
216  }
217 }
218  ''' % path_tail, m)
219  f.close()
220 
221 
222 def generate_MAVLinkMessage(directory, xml_list):
223  f = open(os.path.join(directory, "MAVLinkPacket.java"), mode='w')
224 
225  imports = []
226 
227  for xml in xml_list:
228  importString = "import com.MAVLink.{}.*;".format(xml.basename)
229  imports.append(importString)
230 
231  xml_list[0].importString = os.linesep.join(imports)
232 
233  t.write(f, '''
234 /* AUTO-GENERATED FILE. DO NOT MODIFY.
235  *
236  * This class was automatically generated by the
237  * java mavlink generator tool. It should not be modified by hand.
238  */
239 
240 package com.MAVLink;
241 
242 import java.io.Serializable;
243 import com.MAVLink.Messages.MAVLinkPayload;
244 import com.MAVLink.Messages.MAVLinkMessage;
245 import com.MAVLink.${basename}.CRC;
246 
247 ${importString}
248 
249 /**
250 * Common interface for all MAVLink Messages
251 * Packet Anatomy
252 * This is the anatomy of one packet. It is inspired by the CAN and SAE AS-4 standards.
253 
254 * Byte Index Content Value Explanation
255 * 0 Packet start sign v1.0: 0xFE Indicates the start of a new packet. (v0.9: 0x55)
256 * 1 Payload length 0 - 255 Indicates length of the following payload.
257 * 2 Packet sequence 0 - 255 Each component counts up his send sequence. Allows to detect packet loss
258 * 3 System ID 1 - 255 ID of the SENDING system. Allows to differentiate different MAVs on the same network.
259 * 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.
260 * 5 Message ID 0 - 255 ID of the message - the id defines what the payload means and how it should be correctly decoded.
261 * 6 to (n+6) Payload 0 - 255 Data of the message, depends on the message id.
262 * (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).
263 
264 * 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
265 * The minimum packet length is 8 bytes for acknowledgement packets without payload
266 * The maximum packet length is 263 bytes for full payload
267 *
268 */
269 public class MAVLinkPacket implements Serializable {
270  private static final long serialVersionUID = 2095947771227815314L;
271 
272  public static final int MAVLINK_STX = 254;
273 
274  /**
275  * Message length. NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
276  */
277  public final int len;
278 
279  /**
280  * Message sequence
281  */
282  public int seq;
283 
284  /**
285  * ID of the SENDING system. Allows to differentiate different MAVs on the
286  * same network.
287  */
288  public int sysid;
289 
290  /**
291  * ID of the SENDING component. Allows to differentiate different components
292  * of the same system, e.g. the IMU and the autopilot.
293  */
294  public int compid;
295 
296  /**
297  * ID of the message - the id defines what the payload means and how it
298  * should be correctly decoded.
299  */
300  public int msgid;
301 
302  /**
303  * Data of the message, depends on the message id.
304  */
305  public MAVLinkPayload payload;
306 
307  /**
308  * ITU X.25/SAE AS-4 hash, excluding packet start sign, so bytes 1..(n+6)
309  * Note: The checksum also includes MAVLINK_CRC_EXTRA (Number computed from
310  * message fields. Protects the packet from decoding a different version of
311  * the same packet but with different variables).
312  */
313  public CRC crc;
314 
315  public MAVLinkPacket(int payloadLength){
316  len = payloadLength;
317  payload = new MAVLinkPayload(payloadLength);
318  }
319 
320  /**
321  * Check if the size of the Payload is equal to the "len" byte
322  */
323  public boolean payloadIsFilled() {
324  return payload.size() >= len;
325  }
326 
327  /**
328  * Update CRC for this packet.
329  */
330  public void generateCRC(){
331  if(crc == null){
332  crc = new CRC();
333  }
334  else{
335  crc.start_checksum();
336  }
337 
338  crc.update_checksum(len);
339  crc.update_checksum(seq);
340  crc.update_checksum(sysid);
341  crc.update_checksum(compid);
342  crc.update_checksum(msgid);
343 
344  payload.resetIndex();
345 
346  final int payloadSize = payload.size();
347  for (int i = 0; i < payloadSize; i++) {
348  crc.update_checksum(payload.getByte());
349  }
350  crc.finish_checksum(msgid);
351  }
352 
353  /**
354  * Encode this packet for transmission.
355  *
356  * @return Array with bytes to be transmitted
357  */
358  public byte[] encodePacket() {
359  byte[] buffer = new byte[6 + len + 2];
360 
361  int i = 0;
362  buffer[i++] = (byte) MAVLINK_STX;
363  buffer[i++] = (byte) len;
364  buffer[i++] = (byte) seq;
365  buffer[i++] = (byte) sysid;
366  buffer[i++] = (byte) compid;
367  buffer[i++] = (byte) msgid;
368 
369  final int payloadSize = payload.size();
370  for (int j = 0; j < payloadSize; j++) {
371  buffer[i++] = payload.payload.get(j);
372  }
373 
374  generateCRC();
375  buffer[i++] = (byte) (crc.getLSB());
376  buffer[i++] = (byte) (crc.getMSB());
377  return buffer;
378  }
379 
380  /**
381  * Unpack the data in this packet and return a MAVLink message
382  *
383  * @return MAVLink message decoded from this packet
384  */
385  public MAVLinkMessage unpack() {
386  switch (msgid) {
387  ''', xml_list[0])
388  for xml in xml_list:
389  t.write(f, '''
390  ${{message:
391  case msg_${name_lower}.MAVLINK_MSG_ID_${name}:
392  return new msg_${name_lower}(this);
393  }}
394  ''',xml)
395  f.write('''
396  default:
397  return null;
398  }
399  }
400 
401 }
402 
403  ''')
404 
405  f.close()
406 
407 def copy_fixed_headers(directory, xml):
408  '''copy the fixed protocol headers to the target directory'''
409  import shutil
410  hlist = [ 'Parser.java', 'Messages/MAVLinkMessage.java', 'Messages/MAVLinkPayload.java', 'Messages/MAVLinkStats.java' ]
411  basepath = os.path.dirname(os.path.realpath(__file__))
412  srcpath = os.path.join(basepath, 'java/lib')
413  print("Copying fixed headers")
414  for h in hlist:
415  src = os.path.realpath(os.path.join(srcpath, h))
416  dest = os.path.realpath(os.path.join(directory, h))
417  if src == dest:
418  continue
419  destdir = os.path.realpath(os.path.join(directory, 'Messages'))
420  try:
421  os.makedirs(destdir)
422  except:
423  print("Not re-creating Messages directory")
424  shutil.copy(src, dest)
425 
426 class mav_include(object):
427  def __init__(self, base):
428  self.base = base
429 
430 
431 def mavfmt(field, typeInfo=False):
432  '''work out the struct format for a type'''
433  map = {
434  'float' : ('float', 'Float'),
435  'double' : ('double', 'Double'),
436  'char' : ('byte', 'Byte'),
437  'int8_t' : ('byte', 'Byte'),
438  'uint8_t' : ('short', 'UnsignedByte'),
439  'uint8_t_mavlink_version' : ('short', 'UnsignedByte'),
440  'int16_t' : ('short', 'Short'),
441  'uint16_t' : ('int', 'UnsignedShort'),
442  'int32_t' : ('int', 'Int'),
443  'uint32_t' : ('long', 'UnsignedInt'),
444  'int64_t' : ('long', 'Long'),
445  'uint64_t' : ('long', 'UnsignedLong'),
446  }
447 
448  if typeInfo:
449  return map[field.type][1]
450  else:
451  return map[field.type][0]
452 
453 def generate_one(basename, xml):
454  '''generate headers for one XML file'''
455 
456  directory = os.path.join(basename, xml.basename)
457 
458  print("Generating Java implementation in directory %s" % directory)
459  mavparse.mkdir_p(directory)
460 
461  if xml.little_endian:
462  xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
463  else:
464  xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
465 
466  if xml.crc_extra:
467  xml.crc_extra_define = "1"
468  else:
469  xml.crc_extra_define = "0"
470 
471  if xml.sort_fields:
472  xml.aligned_fields_define = "1"
473  else:
474  xml.aligned_fields_define = "0"
475 
476  # work out the included headers
477  xml.include_list = []
478  for i in xml.include:
479  base = i[:-4]
480  xml.include_list.append(mav_include(base))
481 
482  # form message lengths array
483  xml.message_lengths_array = ''
484  for mlen in xml.message_lengths:
485  xml.message_lengths_array += '%u, ' % mlen
486  xml.message_lengths_array = xml.message_lengths_array[:-2]
487 
488 
489 
490  # form message info array
491  xml.message_info_array = ''
492  for name in xml.message_names:
493  if name is not None:
494  xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
495  else:
496  # Several C compilers don't accept {NULL} for
497  # multi-dimensional arrays and structs
498  # feed the compiler a "filled" empty message
499  xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
500  xml.message_info_array = xml.message_info_array[:-2]
501 
502  # add some extra field attributes for convenience with arrays
503  for m in xml.message:
504  m.msg_name = m.name
505  if xml.crc_extra:
506  m.crc_extra_arg = ", %s" % m.crc_extra
507  else:
508  m.crc_extra_arg = ""
509  for f in m.fields:
510  if f.print_format is None:
511  f.c_print_format = 'NULL'
512  else:
513  f.c_print_format = '"%s"' % f.print_format
514  f.getText = ''
515  if f.array_length != 0:
516  f.array_suffix = '[] = new %s[%u]' % (mavfmt(f),f.array_length)
517  f.array_prefix = '*'
518  f.array_tag = '_array'
519  f.array_arg = ', %u' % f.array_length
520  f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
521  f.array_const = 'const '
522  f.decode_left = ''
523  f.decode_right = 'm.%s' % (f.name)
524 
525  f.unpackField = '''
526  for (int i = 0; i < this.%s.length; i++) {
527  this.%s[i] = payload.get%s();
528  }
529  ''' % (f.name, f.name, mavfmt(f, True) )
530  f.packField = '''
531  for (int i = 0; i < %s.length; i++) {
532  packet.payload.put%s(%s[i]);
533  }
534  ''' % (f.name, mavfmt(f, True),f.name)
535  f.return_type = 'uint16_t'
536  f.get_arg = ', %s *%s' % (f.type, f.name)
537  if f.type == 'char':
538  f.c_test_value = '"%s"' % f.test_value
539  f.getText = '''
540  /**
541  * Sets the buffer of this message with a string, adds the necessary padding
542  */
543  public void set%s(String str) {
544  int len = Math.min(str.length(), %d);
545  for (int i=0; i<len; i++) {
546  %s[i] = (byte) str.charAt(i);
547  }
548 
549  for (int i=len; i<%d; i++) { // padding for the rest of the buffer
550  %s[i] = 0;
551  }
552  }
553 
554  /**
555  * Gets the message, formated as a string
556  */
557  public String get%s() {
558  StringBuffer buf = new StringBuffer();
559  for (int i = 0; i < %d; i++) {
560  if (%s[i] != 0)
561  buf.append((char) %s[i]);
562  else
563  break;
564  }
565  return buf.toString();
566 
567  }
568  ''' % (f.name.title(),f.array_length,f.name,f.array_length,f.name,f.name.title(),f.array_length,f.name,f.name)
569  else:
570  test_strings = []
571  for v in f.test_value:
572  test_strings.append(str(v))
573  f.c_test_value = '{ %s }' % ', '.join(test_strings)
574  else:
575  f.array_suffix = ''
576  f.array_prefix = ''
577  f.array_tag = ''
578  f.array_arg = ''
579  f.array_return_arg = ''
580  f.array_const = ''
581  f.decode_left = '%s' % (f.name)
582  f.decode_right = ''
583  f.unpackField = 'this.%s = payload.get%s();' % (f.name, mavfmt(f, True))
584  f.packField = 'packet.payload.put%s(%s);' % (mavfmt(f, True),f.name)
585 
586 
587  f.get_arg = ''
588  f.return_type = f.type
589  if f.type == 'char':
590  f.c_test_value = "'%s'" % f.test_value
591  elif f.type == 'uint64_t':
592  f.c_test_value = "%sULL" % f.test_value
593  elif f.type == 'int64_t':
594  f.c_test_value = "%sLL" % f.test_value
595  else:
596  f.c_test_value = f.test_value
597 
598  # cope with uint8_t_mavlink_version
599  for m in xml.message:
600  m.arg_fields = []
601  m.array_fields = []
602  m.scalar_fields = []
603  for f in m.ordered_fields:
604  if f.array_length != 0:
605  m.array_fields.append(f)
606  else:
607  m.scalar_fields.append(f)
608  for f in m.fields:
609  if not f.omit_arg:
610  m.arg_fields.append(f)
611  f.putname = f.name
612  else:
613  f.putname = f.const_value
614 
615  # fix types to java
616  for m in xml.message:
617  for f in m.ordered_fields:
618  f.type = mavfmt(f)
619 
620  generate_CRC(directory, xml)
621 
622  for m in xml.message:
623  generate_message_h(directory, m)
624 
625 
626 def generate(basename, xml_list):
627  '''generate complete MAVLink Java implemenation'''
628  for xml in xml_list:
629  generate_one(basename, xml)
630  generate_enums(basename, xml)
631  generate_MAVLinkMessage(basename, xml_list)
632  copy_fixed_headers(basename, xml_list[0])


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