00001
00002 '''
00003 parse a MAVLink protocol XML file and generate a CSharp implementation
00004
00005
00006 '''
00007 import sys, textwrap, os, time, platform
00008 from . import mavparse, mavtemplate
00009
00010 t = mavtemplate.MAVTemplate()
00011
00012
00013 map = {
00014 'float' : 'float',
00015 'double' : 'double',
00016 'char' : 'byte',
00017 'int8_t' : 'sbyte',
00018 'uint8_t' : 'byte',
00019 'uint8_t_mavlink_version' : 'B',
00020 'int16_t' : 'Int16',
00021 'uint16_t' : 'UInt16',
00022 'int32_t' : 'Int32',
00023 'uint32_t' : 'UInt32',
00024 'int64_t' : 'Int64',
00025 'uint64_t' : 'UInt64',
00026 }
00027
00028
00029 mapType = {
00030 'float' : ('ToSingle', 4),
00031 'double' : ('ToDouble', 8),
00032 'int8_t' : ('ToInt8', 1),
00033 'uint8_t' : ('ToUInt8', 1),
00034 'char' : ('ToChar', 1),
00035 'int16_t' : ('ToInt16', 2),
00036 'uint16_t' : ('ToUInt16', 2),
00037 'int32_t' : ('ToInt32', 4),
00038 'uint32_t' : ('ToUInt32', 4),
00039 'int64_t' : ('ToInt64', 8),
00040 'uint64_t' : ('ToUInt64', 8),
00041 }
00042
00043
00044 mapFieldName = {
00045 'fixed' : '@fixed'
00046 }
00047
00048 def generate_preamble(outf, msgs, args, xml):
00049 print("Generating preamble")
00050 t.write(outf, """
00051 /*
00052 MAVLink protocol implementation (auto-generated by mavgen.py)
00053
00054 Generated from: ${FILELIST}
00055
00056 Note: this file has been auto-generated. DO NOT EDIT
00057 */
00058
00059 using System;
00060 """, {'FILELIST' : ",".join(args)})
00061
00062 def generate_xmlDocSummary(outf, summaryText, tabDepth):
00063 indent = '\t' * tabDepth
00064 escapedText = summaryText.replace("\n","\n%s///" % indent)
00065 outf.write("\n%s/// <summary>\n" % indent)
00066 outf.write("%s/// %s\n" % (indent, escapedText))
00067 outf.write("%s/// </summary>\n" % indent)
00068
00069
00070 def generate_enums(outf, enums):
00071 print("Generating enums")
00072 outf.write("namespace MavLink\n{\n")
00073 for e in enums:
00074
00075 generate_xmlDocSummary(outf, e.description, 1)
00076 outf.write("\tpublic enum %s : ushort\n\t{\n" % e.name)
00077
00078 for entry in e.entry:
00079 if len(entry.description) > 0:
00080 generate_xmlDocSummary(outf, entry.description, 2)
00081 outf.write("\t\t%s = %u,\n" % (entry.name, entry.value))
00082
00083 outf.write("\n\t}\n\n")
00084 outf.write("\n}\n")
00085
00086 def generate_classes(outf, msgs):
00087 print("Generating class definitions")
00088
00089 outf.write("""
00090
00091
00092 namespace MavLink\n{
00093
00094 public abstract class MavlinkMessage
00095 {
00096 public abstract int Serialize(byte[] bytes, ref int offset);
00097 }
00098 """)
00099
00100 for m in msgs:
00101 if (len(m.description) >0):
00102 generate_xmlDocSummary(outf, m.description, 1)
00103 outf.write("""\tpublic class Msg_%s : MavlinkMessage
00104 {
00105 """ % m.name.lower())
00106
00107 for f in m.fields:
00108 if (f.description.upper() != f.name.upper()):
00109 generate_xmlDocSummary(outf, f.description, 2)
00110 if (f.array_length):
00111 outf.write("\t\tpublic %s[] %s; // Array size %s\n" % (map[f.type], mapFieldName.get(f.name, f.name), f.array_length))
00112 else:
00113 outf.write("\t\tpublic %s %s;\n" % (map[f.type], mapFieldName.get(f.name, f.name)))
00114
00115 outf.write("""
00116 public override int Serialize(byte[] bytes, ref int offset)
00117 {
00118 return MavLinkSerializer.Serialize_%s(this, bytes, ref offset);
00119 }
00120 """ % m.name.upper())
00121
00122 outf.write("\t}\n\n")
00123 outf.write("}\n\n")
00124
00125
00126
00127 def generate_Deserialization(outf, messages):
00128
00129
00130 for m in messages:
00131 classname="Msg_%s" % m.name.lower()
00132 outf.write("\n\t\tinternal static MavlinkMessage Deserialize_%s(byte[] bytes, int offset)\n\t\t{\n" % (m.name))
00133 offset = 0
00134
00135 outf.write("\t\t\treturn new %s\n" % classname)
00136 outf.write("\t\t\t{\n")
00137
00138 for f in m.ordered_fields:
00139 if (f.array_length):
00140 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))
00141 offset += f.array_length
00142 continue
00143
00144
00145 if (f.type == 'uint8_t' or f.type == 'char' ):
00146 outf.write("\t\t\t\t%s = bytes[offset + %s],\n" % (mapFieldName.get(f.name, f.name),offset))
00147 offset+=1
00148 else:
00149 outf.write("\t\t\t\t%s = bitconverter.%s(bytes, offset + %s),\n" % (mapFieldName.get(f.name, f.name), mapType[f.type][0] , offset))
00150 offset += mapType[f.type][1]
00151
00152 outf.write("\t\t\t};\n")
00153 outf.write("\t\t}\n")
00154
00155
00156 def generate_Serialization(outf, messages):
00157
00158
00159 for m in messages:
00160 classname="Msg_%s" % m.name.lower()
00161
00162 outf.write("\n\t\tinternal static int Serialize_%s(this %s msg, byte[] bytes, ref int offset)\n\t\t{\n" % (m.name, classname))
00163 offset=0
00164
00165
00166 for f in m.ordered_fields:
00167
00168 if (f.array_length):
00169 outf.write("\t\t\tByteArrayUtil.ToByteArray(msg.%s, bytes, offset + %s, %s);\n" % (f.name, offset, f.array_length))
00170 offset += f.array_length * mapType[f.type][1]
00171 continue
00172
00173 if (f.type == 'uint8_t'):
00174 outf.write("\t\t\tbytes[offset + %s] = msg.%s;\n" % (offset,mapFieldName.get(f.name, f.name)))
00175 offset+=1
00176 elif (f.type == 'int8_t'):
00177 outf.write("\t\t\tbytes[offset + %s] = unchecked((byte)msg.%s);\n" % (offset,mapFieldName.get(f.name, f.name)))
00178 offset+=1
00179 elif (f.type == 'char'):
00180 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)))
00181 offset+=1
00182 else:
00183 outf.write("\t\t\tbitconverter.GetBytes(msg.%s, bytes, offset + %s);\n" % (mapFieldName.get(f.name, f.name),offset))
00184 offset += mapType[f.type][1]
00185
00186 outf.write("\t\t\toffset += %s;\n" % offset)
00187 outf.write("\t\t\treturn %s;\n" % m.id)
00188 outf.write("\t\t}\n")
00189
00190
00191 def generate_CodecIndex(outf, messages, xml):
00192
00193 outf.write("""
00194
00195 /*
00196 MAVLink protocol implementation (auto-generated by mavgen.py)
00197
00198 Note: this file has been auto-generated. DO NOT EDIT
00199 */
00200
00201 using System;
00202 using System.Collections;
00203 using System.Collections.Generic;
00204
00205 namespace MavLink
00206 {
00207 public static class MavlinkSettings
00208 {
00209 """)
00210 outf.write('\t\tpublic const string WireProtocolVersion = "%s";' % xml[0].wire_protocol_version)
00211 outf.write('\n\t\tpublic const byte ProtocolMarker = 0x%x;' % xml[0].protocol_marker)
00212 outf.write('\n\t\tpublic const bool CrcExtra = %s;' % str(xml[0].crc_extra).lower())
00213 outf.write('\n\t\tpublic const bool IsLittleEndian = %s;' % str(xml[0].little_endian).lower())
00214
00215 outf.write("""
00216 }
00217
00218 public delegate MavlinkMessage MavlinkPacketDeserializeFunc(byte[] bytes, int offset);
00219
00220 //returns the message ID, offset is advanced by the number of bytes used to serialize
00221 public delegate int MavlinkPacketSerializeFunc(byte[] bytes, ref int offset, object mavlinkPacket);
00222
00223 public class MavPacketInfo
00224 {
00225 public MavlinkPacketDeserializeFunc Deserializer;
00226 public int [] OrderMap;
00227 public byte CrcExtra;
00228
00229 public MavPacketInfo(MavlinkPacketDeserializeFunc deserializer, byte crcExtra)
00230 {
00231 this.Deserializer = deserializer;
00232 this.CrcExtra = crcExtra;
00233 }
00234 }
00235
00236 public static class MavLinkSerializer
00237 {
00238 public static void SetDataIsLittleEndian(bool isLittle)
00239 {
00240 bitconverter.SetDataIsLittleEndian(isLittle);
00241 }
00242
00243 private static readonly FrameworkBitConverter bitconverter = new FrameworkBitConverter();
00244
00245 public static Dictionary<int, MavPacketInfo> Lookup = new Dictionary<int, MavPacketInfo>
00246 {""")
00247
00248 for m in messages:
00249 classname="Msg_%s" % m.name.lower()
00250 outf.write("\n\t\t\t{%s, new MavPacketInfo(Deserialize_%s, %s)}," % (m.id, m.name, m.crc_extra))
00251 outf.write("\n\t\t};\n")
00252
00253
00254 def generate(basename, xml):
00255 '''generate complete MAVLink CSharp implemenation'''
00256 structsfilename = basename + '.generated.cs'
00257
00258
00259 if platform.system() == "Windows":
00260 winpath=os.environ['WinDir']
00261 cscCommand = winpath + "\\Microsoft.NET\\Framework\\v4.0.30319\\csc.exe"
00262
00263 if (os.path.exists(cscCommand)==False):
00264 print("\nError: CS compiler not found. .Net Assembly generation skipped")
00265 return
00266 else:
00267 print("Error:.Net Assembly generation not yet supported on non Windows platforms")
00268 return
00269 cscCommand = "csc"
00270
00271
00272
00273
00274 msgs = []
00275 enums = []
00276 filelist = []
00277 for x in xml:
00278 msgs.extend(x.message)
00279 enums.extend(x.enum)
00280 filelist.append(os.path.basename(x.filename))
00281
00282 for m in msgs:
00283 m.order_map = [ 0 ] * len(m.fieldnames)
00284 for i in range(0, len(m.fieldnames)):
00285 m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
00286
00287 m.fields_in_order = []
00288 for i in range(0, len(m.fieldnames)):
00289 m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
00290
00291 print("Generating messages file: %s" % structsfilename)
00292 dir = os.path.dirname(structsfilename)
00293 if not os.path.exists(dir):
00294 os.makedirs(dir)
00295 outf = open(structsfilename, "w")
00296 generate_preamble(outf, msgs, filelist, xml[0])
00297
00298 outf.write("""
00299
00300 using System.Reflection;
00301
00302 [assembly: AssemblyTitle("Mavlink Classes")]
00303 [assembly: AssemblyDescription("Generated Message Classes for Mavlink. See http://qgroundcontrol.org/mavlink/start")]
00304 [assembly: AssemblyProduct("Mavlink")]
00305 [assembly: AssemblyVersion("1.0.0.0")]
00306 [assembly: AssemblyFileVersion("1.0.0.0")]
00307
00308 """)
00309
00310 generate_enums(outf, enums)
00311 generate_classes(outf, msgs)
00312 outf.close()
00313
00314 print("Generating the (De)Serializer classes")
00315 serfilename = basename + '_codec.generated.cs'
00316 outf = open(serfilename, "w")
00317 generate_CodecIndex(outf, msgs, xml)
00318 generate_Deserialization(outf, msgs)
00319 generate_Serialization(outf, msgs)
00320
00321 outf.write("\t}\n\n")
00322 outf.write("}\n\n")
00323
00324 outf.close()
00325
00326
00327
00328 print("Compiling Assembly for .Net Framework 4.0")
00329
00330 generatedCsFiles = [ serfilename, structsfilename]
00331
00332 includedCsFiles = [ 'CS/common/ByteArrayUtil.cs', 'CS/common/FrameworkBitConverter.cs', 'CS/common/Mavlink.cs' ]
00333
00334 outputLibraryPath = os.path.normpath(dir + "/mavlink.dll")
00335
00336 compileCommand = "%s %s" % (cscCommand, "/target:library /debug /out:" + outputLibraryPath)
00337 compileCommand = compileCommand + " /doc:" + os.path.normpath(dir + "/mavlink.xml")
00338
00339
00340 for csFile in generatedCsFiles + includedCsFiles:
00341 compileCommand = compileCommand + " " + os.path.normpath(csFile)
00342
00343
00344 res = os.system (compileCommand)
00345
00346 if res == '0':
00347 print("Generated %s OK" % filename)
00348 else:
00349 print("Error")