mavgen_cs.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 parse a MAVLink protocol XML file and generate a CSharp implementation
4 
5 
6 '''
7 from __future__ import print_function
8 
9 from builtins import range
10 import os
11 import platform
12 from . import mavtemplate
13 
15 
16 # todo - refactor this in to the other array
17 map = {
18  'float' : 'float',
19  'double' : 'double',
20  'char' : 'byte',
21  'int8_t' : 'sbyte',
22  'uint8_t' : 'byte',
23  'uint8_t_mavlink_version' : 'B',
24  'int16_t' : 'Int16',
25  'uint16_t' : 'UInt16',
26  'int32_t' : 'Int32',
27  'uint32_t' : 'UInt32',
28  'int64_t' : 'Int64',
29  'uint64_t' : 'UInt64',
30  }
31 
32 # Map of field type to bitconverter bytedecoding function, and number of bytes used for the encoding
33 mapType = {
34  'float' : ('ToSingle', 4),
35  'double' : ('ToDouble', 8),
36  'int8_t' : ('ToInt8', 1),
37  'uint8_t' : ('ToUInt8', 1),
38  'char' : ('ToChar', 1),
39  'int16_t' : ('ToInt16', 2),
40  'uint16_t' : ('ToUInt16', 2),
41  'int32_t' : ('ToInt32', 4),
42  'uint32_t' : ('ToUInt32', 4),
43  'int64_t' : ('ToInt64', 8),
44  'uint64_t' : ('ToUInt64', 8),
45  }
46 
47 # Map of field names to names that are C# compatible and not illegal class field names
48 mapFieldName = {
49  'fixed' : '@fixed'
50  }
51 
52 def generate_preamble(outf, msgs, args, xml):
53  print("Generating preamble")
54  t.write(outf, """
55 /*
56 MAVLink protocol implementation (auto-generated by mavgen.py)
57 
58 Generated from: ${FILELIST}
59 
60 Note: this file has been auto-generated. DO NOT EDIT
61 */
62 
63 using System;
64 """, {'FILELIST' : ",".join(args)})
65 
66 def generate_xmlDocSummary(outf, summaryText, tabDepth):
67  indent = '\t' * tabDepth
68  escapedText = summaryText.replace("\n","\n%s///" % indent)
69  outf.write("\n%s/// <summary>\n" % indent)
70  outf.write("%s/// %s\n" % (indent, escapedText))
71  outf.write("%s/// </summary>\n" % indent)
72 
73 
74 def generate_enums(outf, enums):
75  print("Generating enums")
76  outf.write("namespace MavLink\n{\n")
77  for e in enums:
78  #if len(e.description) > 0:
79  generate_xmlDocSummary(outf, e.description, 1)
80  outf.write("\tpublic enum %s : uint\n\t{\n" % e.name)
81 
82  for entry in e.entry:
83  if len(entry.description) > 0:
84  generate_xmlDocSummary(outf, entry.description, 2)
85  outf.write("\t\t%s = %u,\n" % (entry.name, entry.value))
86 
87  outf.write("\n\t}\n\n")
88  outf.write("\n}\n")
89 
90 def generate_classes(outf, msgs):
91  print("Generating class definitions")
92 
93  outf.write("""
94 
95 
96 namespace MavLink\n{
97 
98  public abstract class MavlinkMessage
99  {
100  public abstract int Serialize(byte[] bytes, ref int offset);
101  }
102 """)
103 
104  for m in msgs:
105  if (len(m.description) >0):
106  generate_xmlDocSummary(outf, m.description, 1)
107  outf.write("""\tpublic class Msg_%s : MavlinkMessage
108  {
109 """ % m.name.lower())
110 
111  for f in m.fields:
112  if (f.description.upper() != f.name.upper()):
113  generate_xmlDocSummary(outf, f.description, 2)
114  if (f.array_length):
115  outf.write("\t\tpublic %s[] %s; // Array size %s\n" % (map[f.type], mapFieldName.get(f.name, f.name), f.array_length))
116  else:
117  outf.write("\t\tpublic %s %s;\n" % (map[f.type], mapFieldName.get(f.name, f.name)))
118 
119  outf.write("""
120  public override int Serialize(byte[] bytes, ref int offset)
121  {
122  return MavLinkSerializer.Serialize_%s(this, bytes, ref offset);
123  }
124 """ % m.name.upper())
125 
126  outf.write("\t}\n\n")
127  outf.write("}\n\n")
128 
129 
130 
131 def generate_Deserialization(outf, messages):
132 
133  # Create the deserialization funcs
134  for m in messages:
135  classname="Msg_%s" % m.name.lower()
136  outf.write("\n\t\tinternal static MavlinkMessage Deserialize_%s(byte[] bytes, int offset)\n\t\t{\n" % (m.name))
137  offset = 0
138 
139  outf.write("\t\t\treturn new %s\n" % classname)
140  outf.write("\t\t\t{\n")
141 
142  for f in m.ordered_fields:
143  if (f.array_length):
144  outf.write("\t\t\t\t%s = ByteArrayUtil.%s(bytes, offset + %s, %s),\n" % (mapFieldName.get(f.name, f.name), mapType[f.type][0], offset, f.array_length))
145  offset += (f.array_length * mapType[f.type][1])
146  continue
147 
148  # mapping 'char' to byte here since there is no real equivalent in the CLR
149  if (f.type == 'uint8_t' or f.type == 'char' ):
150  outf.write("\t\t\t\t%s = bytes[offset + %s],\n" % (mapFieldName.get(f.name, f.name),offset))
151  offset+=1
152  else:
153  outf.write("\t\t\t\t%s = bitconverter.%s(bytes, offset + %s),\n" % (mapFieldName.get(f.name, f.name), mapType[f.type][0] , offset))
154  offset += mapType[f.type][1]
155 
156  outf.write("\t\t\t};\n")
157  outf.write("\t\t}\n")
158 
159 
160 def generate_Serialization(outf, messages):
161 
162  # Create the table of serialization delegates
163  for m in messages:
164  classname="Msg_%s" % m.name.lower()
165 
166  outf.write("\n\t\tinternal static int Serialize_%s(this %s msg, byte[] bytes, ref int offset)\n\t\t{\n" % (m.name, classname))
167  offset=0
168 
169  # Now (since Mavlink 1.0) we need to deal with ordering of fields
170  for f in m.ordered_fields:
171 
172  if (f.array_length):
173  outf.write("\t\t\tByteArrayUtil.ToByteArray(msg.%s, bytes, offset + %s, %s);\n" % (f.name, offset, f.array_length))
174  offset += f.array_length * mapType[f.type][1]
175  continue
176 
177  if (f.type == 'uint8_t'):
178  outf.write("\t\t\tbytes[offset + %s] = msg.%s;\n" % (offset,mapFieldName.get(f.name, f.name)))
179  offset+=1
180  elif (f.type == 'int8_t'):
181  outf.write("\t\t\tbytes[offset + %s] = unchecked((byte)msg.%s);\n" % (offset,mapFieldName.get(f.name, f.name)))
182  offset+=1
183  elif (f.type == 'char'):
184  outf.write("\t\t\tbytes[offset + %s] = msg.%s; // todo: check int8_t and char are compatible\n" % (offset,mapFieldName.get(f.name, f.name)))
185  offset+=1
186  else:
187  outf.write("\t\t\tbitconverter.GetBytes(msg.%s, bytes, offset + %s);\n" % (mapFieldName.get(f.name, f.name),offset))
188  offset += mapType[f.type][1]
189 
190  outf.write("\t\t\toffset += %s;\n" % offset)
191  outf.write("\t\t\treturn %s;\n" % m.id)
192  outf.write("\t\t}\n")
193 
194 
195 def generate_CodecIndex(outf, messages, xml):
196 
197  outf.write("""
198 
199 /*
200 MAVLink protocol implementation (auto-generated by mavgen.py)
201 
202 Note: this file has been auto-generated. DO NOT EDIT
203 */
204 
205 using System;
206 using System.Collections;
207 using System.Collections.Generic;
208 
209 namespace MavLink
210 {
211  public static class MavlinkSettings
212  {
213 """)
214  outf.write('\t\tpublic const string WireProtocolVersion = "%s";' % xml[0].wire_protocol_version)
215  outf.write('\n\t\tpublic const byte ProtocolMarker = 0x%x;' % xml[0].protocol_marker)
216  outf.write('\n\t\tpublic const bool CrcExtra = %s;' % str(xml[0].crc_extra).lower())
217  outf.write('\n\t\tpublic const bool IsLittleEndian = %s;' % str(xml[0].little_endian).lower())
218 
219  outf.write("""
220  }
221 
222  public delegate MavlinkMessage MavlinkPacketDeserializeFunc(byte[] bytes, int offset);
223 
224  //returns the message ID, offset is advanced by the number of bytes used to serialize
225  public delegate int MavlinkPacketSerializeFunc(byte[] bytes, ref int offset, object mavlinkPacket);
226 
227  public class MavPacketInfo
228  {
229  public MavlinkPacketDeserializeFunc Deserializer;
230  public int [] OrderMap;
231  public byte CrcExtra;
232 
233  public MavPacketInfo(MavlinkPacketDeserializeFunc deserializer, byte crcExtra)
234  {
235  this.Deserializer = deserializer;
236  this.CrcExtra = crcExtra;
237  }
238  }
239 
240  public static class MavLinkSerializer
241  {
242  public static void SetDataIsLittleEndian(bool isLittle)
243  {
244  bitconverter.SetDataIsLittleEndian(isLittle);
245  }
246 
247  private static readonly FrameworkBitConverter bitconverter = new FrameworkBitConverter();
248 
249  public static Dictionary<int, MavPacketInfo> Lookup = new Dictionary<int, MavPacketInfo>
250  {""")
251 
252  for m in messages:
253  classname="Msg_%s" % m.name.lower()
254  outf.write("\n\t\t\t{%s, new MavPacketInfo(Deserialize_%s, %s)}," % (m.id, m.name, m.crc_extra))
255  outf.write("\n\t\t};\n")
256 
257 
258 def generate(basename, xml):
259  '''generate complete MAVLink CSharp implemenation'''
260  structsfilename = basename + '.generated.cs'
261 
262  msgs = []
263  enums = []
264  filelist = []
265  for x in xml:
266  msgs.extend(x.message)
267  enums.extend(x.enum)
268  filelist.append(os.path.basename(x.filename))
269 
270  for m in msgs:
271  m.order_map = [ 0 ] * len(m.fieldnames)
272  for i in range(0, len(m.fieldnames)):
273  m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
274 
275  m.fields_in_order = []
276  for i in range(0, len(m.fieldnames)):
277  m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
278 
279  print("Generating messages file: %s" % structsfilename)
280  dir = os.path.dirname(structsfilename)
281  if not os.path.exists(dir):
282  os.makedirs(dir)
283  outf = open(structsfilename, "w")
284  generate_preamble(outf, msgs, filelist, xml[0])
285 
286  outf.write("""
287 
288 using System.Reflection;
289 
290 [assembly: AssemblyTitle("Mavlink Classes")]
291 [assembly: AssemblyDescription("Generated Message Classes for Mavlink. See http://qgroundcontrol.org/mavlink/start")]
292 [assembly: AssemblyProduct("Mavlink")]
293 [assembly: AssemblyVersion("1.0.0.0")]
294 [assembly: AssemblyFileVersion("1.0.0.0")]
295 
296  """)
297 
298  generate_enums(outf, enums)
299  generate_classes(outf, msgs)
300  outf.close()
301 
302  print("Generating the (De)Serializer classes")
303  serfilename = basename + '_codec.generated.cs'
304  outf = open(serfilename, "w")
305  generate_CodecIndex(outf, msgs, xml)
306  generate_Deserialization(outf, msgs)
307  generate_Serialization(outf, msgs)
308 
309  outf.write("\t}\n\n")
310  outf.write("}\n\n")
311 
312  outf.close()
313 
314  # Some build commands depend on the platform - eg MS .NET Windows Vs Mono on Linux
315  if platform.system() == "Windows":
316  winpath=os.environ['WinDir']
317  cscCommand = winpath + "\\Microsoft.NET\\Framework\\v4.0.30319\\csc.exe"
318 
319  if not os.path.exists(cscCommand):
320  print("\nError: CS compiler not found. .Net Assembly generation skipped")
321  return
322  else:
323  print("Error:.Net Assembly generation not yet supported on non Windows platforms")
324  return
325  cscCommand = "csc"
326 
327  print("Compiling Assembly for .Net Framework 4.0")
328 
329  generatedCsFiles = [ serfilename, structsfilename]
330 
331  includedCsFiles = [ 'CS/common/ByteArrayUtil.cs', 'CS/common/FrameworkBitConverter.cs', 'CS/common/Mavlink.cs' ]
332 
333  outputLibraryPath = os.path.normpath(dir + "/mavlink.dll")
334 
335  compileCommand = "%s %s" % (cscCommand, "/target:library /debug /out:" + outputLibraryPath)
336  compileCommand = compileCommand + " /doc:" + os.path.normpath(dir + "/mavlink.xml")
337 
338  for csFile in generatedCsFiles + includedCsFiles:
339  compileCommand = compileCommand + " " + os.path.normpath(csFile)
340 
341  #print("Cmd:" + compileCommand)
342  res = os.system (compileCommand)
343 
344  if res == 0:
345  print("Generated %s OK" % outputLibraryPath)
346  else:
347  print("Error")
348  print("Error: Compilation failed. (" + str(res) + ")")
349  raise SystemError("Compilation failed. (" + str(res) + ")")


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