#if !NET4 && !NET45 using System; using System.Reflection; using System.Runtime.InteropServices; //using log4net; namespace Plane.Protocols { /// /// Static methods and helpers for creation and manipulation of Mavlink packets /// internal static class MavlinkUtil { //private static readonly ILog log = // LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); /// /// Create a new mavlink packet object from a byte array as recieved over mavlink /// Endianess will be detetected using packet inspection /// /// The type of mavlink packet to create /// The bytes of the mavlink packet /// The position in the byte array where the packet starts /// The newly created mavlink packet internal static TMavlinkPacket ByteArrayToStructure(this byte[] bytearray, int startoffset = 6) where TMavlinkPacket : struct { if (bytearray[0] == 'U' && startoffset == 6 ) { throw new NotSupportedException("bytearray[0] == 'U' is not supported."); //ByteArrayToStructureEndian(bytearray, ref obj, startoffset); } else { int len = Marshal.SizeOf(); IntPtr i = Marshal.AllocHGlobal(len); TMavlinkPacket packet; try { // copy byte array to ptr Marshal.Copy(bytearray, startoffset, i, len); packet = Marshal.PtrToStructure(i); } // 林俊清, 20151026, 改为不吞异常了。 //catch //{ // //log.Error("ByteArrayToStructure FAIL", ex); //} finally { Marshal.FreeHGlobal(i); } return packet; } } internal static TMavlinkPacket ByteArrayToStructureBigEndian(this byte[] bytearray, int startoffset = 6) where TMavlinkPacket : struct { object newPacket = new TMavlinkPacket(); throw new NotSupportedException("ByteArrayToStructureBigEndian is not supported."); //ByteArrayToStructureEndian(bytearray, ref newPacket, startoffset); //return (TMavlinkPacket)newPacket; } //internal static void ByteArrayToStructureEndian(byte[] bytearray, ref object obj, int startoffset) //{ // int len = Marshal.SizeOf(obj); // IntPtr i = Marshal.AllocHGlobal(len); // byte[] temparray = (byte[])bytearray.Clone(); // // create structure from ptr // obj = Marshal.PtrToStructure(i, obj.GetType()); // // do endian swap // object thisBoxed = obj; // Type test = thisBoxed.GetType(); // int reversestartoffset = startoffset; // // Enumerate each structure field using reflection. // foreach (var field in test.GetRuntimeFields()) // { // // field.Name has the field's name. // object fieldValue = field.GetValue(thisBoxed); // Get value // // Get the TypeCode enumeration. Multiple types get mapped to a common typecode. // TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType()); // if (typeCode != TypeCode.Object) // { // Array.Reverse(temparray, reversestartoffset, Marshal.SizeOf(fieldValue)); // reversestartoffset += Marshal.SizeOf(fieldValue); // } // else // { // reversestartoffset += ((byte[])fieldValue).Length; // } // } // try // { // // copy byte array to ptr // Marshal.Copy(temparray, startoffset, i, len); // } // catch // { // //log.Error("ByteArrayToStructure FAIL", ex); // } // obj = Marshal.PtrToStructure(i, obj.GetType()); // Marshal.FreeHGlobal(i); //} /// /// Convert a struct to an array of bytes, struct fields being reperesented in /// little endian (LSB first) /// /// Note - assumes little endian host order internal static byte[] StructureToByteArray(TMavlinkPacket packet) { int len = Marshal.SizeOf(packet); byte[] arr = new byte[len]; IntPtr ptr = Marshal.AllocHGlobal(len); try { Marshal.StructureToPtr(packet, ptr, true); Marshal.Copy(ptr, arr, 0, len); } finally { Marshal.FreeHGlobal(ptr); } return arr; } /// /// Convert a struct to an array of bytes, struct fields being reperesented in /// big endian (MSB first) /// internal static byte[] StructureToByteArrayBigEndian(TMavlinkPacket packet) { //// The copy is made becuase SetValue won't work on a struct. //// Boxing was used because SetValue works on classes/objects. //// Unfortunately, it results in 2 copy operations. //object thisBoxed = list[0]; // Why make a copy? object thisBoxed = packet; Type test = thisBoxed.GetType(); int offset = 0; byte[] data = new byte[Marshal.SizeOf(packet)]; object fieldValue; //TypeCode typeCode; byte[] temp; // Enumerate each structure field using reflection. foreach (var field in test.GetFields()) { // field.Name has the field's name. fieldValue = field.GetValue(thisBoxed); // Get value //// Get the TypeCode enumeration. Multiple types get mapped to a common typecode. //typeCode = Type.GetTypeCode(fieldValue.GetType()); //switch (typeCode) switch (fieldValue.GetType().Name) { case nameof(Single): // float { temp = BitConverter.GetBytes((Single)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(Single)); offset += Marshal.SizeOf(); break; } case nameof(Int32): { temp = BitConverter.GetBytes((Int32)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(Int32)); offset += Marshal.SizeOf(); break; } case nameof(UInt32): { temp = BitConverter.GetBytes((UInt32)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(UInt32)); offset += Marshal.SizeOf(); break; } case nameof(Int16): { temp = BitConverter.GetBytes((Int16)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(Int16)); offset += Marshal.SizeOf(); break; } case nameof(UInt16): { temp = BitConverter.GetBytes((UInt16)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(UInt16)); offset += Marshal.SizeOf(); break; } case nameof(Int64): { temp = BitConverter.GetBytes((Int64)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(Int64)); offset += Marshal.SizeOf(); break; } case nameof(UInt64): { temp = BitConverter.GetBytes((UInt64)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(UInt64)); offset += Marshal.SizeOf(); break; } case nameof(Double): { temp = BitConverter.GetBytes((Double)fieldValue); Array.Reverse(temp); Array.Copy(temp, 0, data, offset, sizeof(Double)); offset += Marshal.SizeOf(); break; } case nameof(Byte): { data[offset] = (Byte)fieldValue; offset += Marshal.SizeOf(); break; } default: { int length = ((byte[])fieldValue).Length; Array.Copy(((byte[])fieldValue), 0, data, offset, length); offset += length; //System.Diagnostics.Debug.Fail("No conversion provided for this type : " + typeCode.ToString()); break; } }; // switch } // foreach return data; } // Swap } } #endif