3 parse a MAVLink protocol XML file and generate a CSharp implementation 7 from __future__
import print_function
9 from builtins
import range
12 from .
import mavtemplate
23 'uint8_t_mavlink_version' :
'B',
25 'uint16_t' :
'UInt16',
27 'uint32_t' :
'UInt32',
29 'uint64_t' :
'UInt64',
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),
53 print(
"Generating preamble")
56 MAVLink protocol implementation (auto-generated by mavgen.py) 58 Generated from: ${FILELIST} 60 Note: this file has been auto-generated. DO NOT EDIT 64 """, {
'FILELIST' :
",".join(args)})
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)
75 print(
"Generating enums")
76 outf.write(
"namespace MavLink\n{\n")
80 outf.write(
"\tpublic enum %s : uint\n\t{\n" % e.name)
83 if len(entry.description) > 0:
85 outf.write(
"\t\t%s = %u,\n" % (entry.name, entry.value))
87 outf.write(
"\n\t}\n\n")
91 print(
"Generating class definitions")
98 public abstract class MavlinkMessage 100 public abstract int Serialize(byte[] bytes, ref int offset); 105 if (len(m.description) >0):
107 outf.write(
"""\tpublic class Msg_%s : MavlinkMessage 109 """ % m.name.lower())
112 if (f.description.upper() != f.name.upper()):
115 outf.write(
"\t\tpublic %s[] %s; // Array size %s\n" % (map[f.type], mapFieldName.get(f.name, f.name), f.array_length))
117 outf.write(
"\t\tpublic %s %s;\n" % (map[f.type], mapFieldName.get(f.name, f.name)))
120 public override int Serialize(byte[] bytes, ref int offset) 122 return MavLinkSerializer.Serialize_%s(this, bytes, ref offset); 124 """ % m.name.upper())
126 outf.write(
"\t}\n\n")
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))
139 outf.write(
"\t\t\treturn new %s\n" % classname)
140 outf.write(
"\t\t\t{\n")
142 for f
in m.ordered_fields:
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])
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))
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]
156 outf.write(
"\t\t\t};\n")
157 outf.write(
"\t\t}\n")
164 classname=
"Msg_%s" % m.name.lower()
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))
170 for f
in m.ordered_fields:
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]
177 if (f.type ==
'uint8_t'):
178 outf.write(
"\t\t\tbytes[offset + %s] = msg.%s;\n" % (offset,mapFieldName.get(f.name, f.name)))
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)))
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)))
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]
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")
200 MAVLink protocol implementation (auto-generated by mavgen.py) 202 Note: this file has been auto-generated. DO NOT EDIT 206 using System.Collections; 207 using System.Collections.Generic; 211 public static class MavlinkSettings 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())
222 public delegate MavlinkMessage MavlinkPacketDeserializeFunc(byte[] bytes, int offset); 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); 227 public class MavPacketInfo 229 public MavlinkPacketDeserializeFunc Deserializer; 230 public int [] OrderMap; 231 public byte CrcExtra; 233 public MavPacketInfo(MavlinkPacketDeserializeFunc deserializer, byte crcExtra) 235 this.Deserializer = deserializer; 236 this.CrcExtra = crcExtra; 240 public static class MavLinkSerializer 242 public static void SetDataIsLittleEndian(bool isLittle) 244 bitconverter.SetDataIsLittleEndian(isLittle); 247 private static readonly FrameworkBitConverter bitconverter = new FrameworkBitConverter(); 249 public static Dictionary<int, MavPacketInfo> Lookup = new Dictionary<int, MavPacketInfo> 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")
259 '''generate complete MAVLink CSharp implemenation''' 260 structsfilename = basename +
'.generated.cs' 266 msgs.extend(x.message)
268 filelist.append(os.path.basename(x.filename))
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])
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])
279 print(
"Generating messages file: %s" % structsfilename)
280 dir = os.path.dirname(structsfilename)
281 if not os.path.exists(dir):
283 outf = open(structsfilename,
"w")
288 using System.Reflection; 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")] 302 print(
"Generating the (De)Serializer classes")
303 serfilename = basename +
'_codec.generated.cs' 304 outf = open(serfilename,
"w")
309 outf.write(
"\t}\n\n")
315 if platform.system() ==
"Windows":
316 winpath=os.environ[
'WinDir']
317 cscCommand = winpath +
"\\Microsoft.NET\\Framework\\v4.0.30319\\csc.exe" 319 if not os.path.exists(cscCommand):
320 print(
"\nError: CS compiler not found. .Net Assembly generation skipped")
323 print(
"Error:.Net Assembly generation not yet supported on non Windows platforms")
327 print(
"Compiling Assembly for .Net Framework 4.0")
329 generatedCsFiles = [ serfilename, structsfilename]
331 includedCsFiles = [
'CS/common/ByteArrayUtil.cs',
'CS/common/FrameworkBitConverter.cs',
'CS/common/Mavlink.cs' ]
333 outputLibraryPath = os.path.normpath(dir +
"/mavlink.dll")
335 compileCommand =
"%s %s" % (cscCommand,
"/target:library /debug /out:" + outputLibraryPath)
336 compileCommand = compileCommand +
" /doc:" + os.path.normpath(dir +
"/mavlink.xml")
338 for csFile
in generatedCsFiles + includedCsFiles:
339 compileCommand = compileCommand +
" " + os.path.normpath(csFile)
342 res = os.system (compileCommand)
345 print(
"Generated %s OK" % outputLibraryPath)
348 print(
"Error: Compilation failed. (" +
str(res) +
")")
349 raise SystemError(
"Compilation failed. (" +
str(res) +
")")
def generate_xmlDocSummary(outf, summaryText, tabDepth)
def generate_preamble(outf, msgs, args, xml)
def generate_Deserialization(outf, messages)
def generate_CodecIndex(outf, messages, xml)
def generate_enums(outf, enums)
def generate(basename, xml)
def generate_Serialization(outf, messages)
def generate_classes(outf, msgs)