Skip to content

Commit

Permalink
Merge branch 'master' into add-adsb-http
Browse files Browse the repository at this point in the history
  • Loading branch information
MUSTARDTIGERFPV authored Nov 26, 2024
2 parents e30764e + 5c46b09 commit f70ecb1
Show file tree
Hide file tree
Showing 52 changed files with 35,680 additions and 21,473 deletions.
7 changes: 5 additions & 2 deletions Controls/DevopsUI.cs
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,15 @@ public DevopsUI()
private void but_doit_Click(object sender, EventArgs e)
{
var buffer = new byte[Convert.ToByte(num_count.Text)];
MainV2.comPort.device_op(Convert.ToByte(num_sysid.Text), Convert.ToByte(num_compid.Text), out buffer,
var result = MainV2.comPort.device_op(Convert.ToByte(num_sysid.Text), Convert.ToByte(num_compid.Text), out buffer,
dom_bustype.Text == "SPI" ? MAVLink.DEVICE_OP_BUSTYPE.SPI : MAVLink.DEVICE_OP_BUSTYPE.I2C,
txt_spiname.Text, Convert.ToByte(num_busno.Text), Convert.ToByte(num_address.Text),
Convert.ToByte(num_regstart.Text), Convert.ToByte(num_count.Text));

textBox1.AppendText(buffer.Select(a => a.ToString("X2")).Aggregate((a, b) => a + b) + "\r\n");
if (buffer.Length > 0)
textBox1.AppendText(buffer.Select(a => a.ToString("X2")).Aggregate((a, b) => a + b) + "\r\n");
else
textBox1.AppendText("No Responce - " + result + "\r\n");
}

private void dom_bustype_SelectedItemChanged(object sender, EventArgs e)
Expand Down
27 changes: 14 additions & 13 deletions Controls/OpenGLtest2.cs
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ static int generateTexture(Bitmap image)
}

static void ConvertColorSpace(BitmapData _data)
{
{
// bgra to rgba
var x = 0; var y = 0; var width = _data.Width; var height = _data.Height;
for (y = 0; y < height; y++)
Expand Down Expand Up @@ -295,7 +295,7 @@ static int CreateTexture(BitmapData data)
}
else
{
// No, it's not a power of 2. Turn of mips and set wrapping to clamp to edge
// No, it's not a power of 2. Turn of mips and set wrapping to clamp to edge
GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
}
return texture;
Expand All @@ -310,7 +310,7 @@ static int FloorPowerOf2(int value)
{
var ans = Math.Log(value, 2);

return (int)Math.Pow(2, Math.Floor(ans));
return (int)Math.Pow(2, Math.Floor(ans));
}

[MethodImpl(MethodImplOptions.AggressiveInlining)]
Expand Down Expand Up @@ -519,7 +519,7 @@ public void doPaint()
/*Console.WriteLine("cam: {0} {1} {2} lookat: {3} {4} {5}", (float) cameraX, (float) cameraY, (float) cameraZ,
(float) lookX,
(float) lookY, (float) lookZ);
*/
*/
modelMatrix = Matrix4.LookAt((float) cameraX, (float) cameraY, (float) cameraZ + 100f * 0,
(float) lookX, (float) lookY, (float) lookZ,
0, 0, 1);
Expand All @@ -539,7 +539,7 @@ public void doPaint()
GL.ClearColor(Color.CornflowerBlue);
GL.Clear(ClearBufferMask.ColorBufferBit | ClearBufferMask.DepthBufferBit |
ClearBufferMask.AccumBufferBit);

// disable depth during terrain draw
GL.Disable(EnableCap.DepthTest);
GL.DepthFunc(DepthFunction.Lequal);
Expand Down Expand Up @@ -642,7 +642,7 @@ public void doPaint()
startindex + 1, startindex + 3, startindex + 2
});


wpmarker.Draw(projMatrix, modelMatrix);

wpmarker.Cleanup(true);
Expand Down Expand Up @@ -696,7 +696,7 @@ private double[] projectLocation(double[] oldpos)
var factor = 0.3;
return new double[]
{
oldpos[0] * factor + newpos[0] * (1.0 - factor),
oldpos[0] * factor + newpos[0] * (1.0 - factor),
oldpos[1] * factor + newpos[1] * (1.0 - factor),
oldpos[2] * factor + newpos[2] * (1.0 - factor)
};
Expand Down Expand Up @@ -758,7 +758,7 @@ private void generateTextures()
if (DateTime.Now.Second % 3 == 1)
CleanupOldTextures(tileArea);
}

//https://wiki.openstreetmap.org/wiki/Zoom_levels
var C = 2 * Math.PI * 6378137.000;
// horizontal distance by each tile square
Expand All @@ -775,6 +775,7 @@ private void generateTextures()
stile = C * Math.Cos(_center.Lat) / Math.Pow(2, tilearea.zoom);
pxstep = (int)(stile / 45);
pxstep = FloorPowerOf2(pxstep);
if (pxstep == int.MinValue) pxstep = 0;
if (pxstep == 0)
pxstep = 1;
foreach (var p in tilearea.points)
Expand Down Expand Up @@ -879,7 +880,7 @@ private void generateTextures()

private void Minimumtile(List<tileZoomArea> tileArea)
{
foreach (tileZoomArea tileZoomArea in tileArea.Reverse<tileZoomArea>())
foreach (tileZoomArea tileZoomArea in tileArea.Reverse<tileZoomArea>())
{
//GPoint centerPixel = Provider.Projection.FromLatLngToPixel(center, Zoom);
//var centerTileXYLocation = Provider.Projection.FromPixelToTileXY(centerPixel);
Expand Down Expand Up @@ -1669,9 +1670,9 @@ void main(void) {
}

GL.UseProgram(_program);
positionSlot = GL.GetAttribLocation(_program, "Position");
colorSlot = GL.GetAttribLocation(_program, "SourceColor");
texCoordSlot = GL.GetAttribLocation(_program, "TexCoordIn");
positionSlot = GL.GetAttribLocation(_program, "Position");
colorSlot = GL.GetAttribLocation(_program, "SourceColor");
texCoordSlot = GL.GetAttribLocation(_program, "TexCoordIn");
projectionSlot = GL.GetUniformLocation(_program, "Projection");
modelViewSlot = GL.GetUniformLocation(_program, "ModelView");
textureSlot = GL.GetUniformLocation(_program, "Texture");
Expand Down Expand Up @@ -1716,7 +1717,7 @@ public void Cleanup(bool nolock = false)
public void Dispose()
{
Cleanup();
}
}
}

[StructLayout(LayoutKind.Sequential, Pack = 1)]
Expand Down
6 changes: 4 additions & 2 deletions Controls/SerialOutputNMEA.cs
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
using MissionPlanner.Comms;
using GeoidHeightsDotNet;
using MissionPlanner.Comms;
using MissionPlanner.Utilities;
using System;
using System.Globalization;
Expand Down Expand Up @@ -144,7 +145,8 @@ void mainloop()
DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100).ToString("0000.00000", CultureInfo.InvariantCulture), MainV2.comPort.MAV.cs.lat < 0 ? "S" : "N",
Math.Abs(lng * 100).ToString("00000.00000", CultureInfo.InvariantCulture), MainV2.comPort.MAV.cs.lng < 0 ? "W" : "E",
MainV2.comPort.MAV.cs.gpsstatus >= 3 ? 1 : 0, MainV2.comPort.MAV.cs.satcount,
MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.altasl, "M", 0, "M", "");
MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.altasl / CurrentState.multiplieralt, "M",
GeoidHeights.undulation(MainV2.comPort.MAV.cs.lat, MainV2.comPort.MAV.cs.lng).ToString("0.0", CultureInfo.InvariantCulture), "M", "");

string checksum = GetChecksum(line);
NmeaStream.WriteLine(line + "*" + checksum+"\r");
Expand Down
9 changes: 9 additions & 0 deletions Controls/SerialOutputPass.Designer.cs

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

58 changes: 40 additions & 18 deletions Controls/SerialOutputPass.cs
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
using Microsoft.Scripting.Utils;
using DeviceProgramming.Dfu;
using Microsoft.Scripting.Utils;
using MissionPlanner.Comms;
using MissionPlanner.Utilities;
using Newtonsoft.Json;
Expand Down Expand Up @@ -131,15 +132,17 @@ private void BUT_connect_Click(object sender, EventArgs e)
void DoAcceptTcpClientCallback(IAsyncResult ar)
{
// Get the listener that handles the client request.
TcpListener listener = (TcpListener)ar.AsyncState;
var state = (ValueTuple<TcpListener, MAVLinkInterface.Mirror>)ar.AsyncState;
TcpListener listener = state.Item1;
MAVLinkInterface.Mirror mirror = state.Item2;

// End the operation and display the received data on
// the console.
TcpClient client = listener.EndAcceptTcpClient(ar);

((TcpSerial)MainV2.comPort.MirrorStream).client = client;
((TcpSerial)mirror.MirrorStream).client = client;

listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), listener);
listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), state);
}

private void chk_write_CheckedChanged(object sender, EventArgs e)
Expand All @@ -165,7 +168,7 @@ private void Save()
Settings.Instance.SetList(configlist, ans);
}

private void Load()
private void Load()
{
var ans = Settings.Instance.GetList(configlist);

Expand All @@ -174,11 +177,17 @@ private void Load()
if (row == null || row == "")
continue;
var data = ((JArray)JsonConvert.DeserializeObject(row)).Select(a => ((JValue)a).Value).ToArray();
myDataGridView1.Rows.Add(data);
var index = myDataGridView1.Rows.Add(data);

if (Started.Contains(index))
{
myDataGridView1[Go.Index, index].Value = "Started";
}
}
}

string configlist = "serialpasslist";
static private List<int> Started = new List<int>();

private void myDataGridView1_DataError(object sender, DataGridViewDataErrorEventArgs e)
{
Expand All @@ -191,26 +200,31 @@ private void myDataGridView1_CellContentClick(object sender, DataGridViewCellEve
{
try
{
MAVLinkInterface.Mirror mirror = new MAVLinkInterface.Mirror();

var protocol = myDataGridView1[Type.Index, e.RowIndex].Value.ToString();
var direction = myDataGridView1[Direction.Index, e.RowIndex].Value.ToString();
var port = myDataGridView1[Port.Index, e.RowIndex].Value.ToString();
var extra = myDataGridView1[Extra.Index, e.RowIndex].Value.ToString();
var write = myDataGridView1[Write.Index, e.RowIndex].Value.ToString();
if (protocol == "TCP")
{
if (direction == "Inbound")
{
MainV2.comPort.MirrorStream = new TcpSerial();
{
mirror.MirrorStream = new TcpSerial();
mirror.MirrorStreamWrite = bool.Parse(write);
CMB_baudrate.SelectedIndex = 0;
listener = new TcpListener(System.Net.IPAddress.Any, int.Parse(port.ToString()));
listener.Start(0);
listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), listener);
listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), (listener, mirror));
BUT_connect.Text = Strings.Stop;
}
else if (direction == "Outbound")
{
MainV2.comPort.MirrorStream = new TcpSerial() { retrys = 999999, autoReconnect = true, Host = extra, Port = port, ConfigRef = "SerialOutputPassTCP" };
mirror.MirrorStream = new TcpSerial() { retrys = 999999, autoReconnect = true, Host = extra, Port = port, ConfigRef = "SerialOutputPassTCP" };
CMB_baudrate.SelectedIndex = 0;
MainV2.comPort.MirrorStream.Open();
mirror.MirrorStream.Open();
mirror.MirrorStreamWrite = bool.Parse(write);
}
}
else if (protocol == "UDP")
Expand All @@ -220,27 +234,35 @@ private void myDataGridView1_CellContentClick(object sender, DataGridViewCellEve
var udp = new UdpSerial()
{ ConfigRef = "SerialOutputPassUDP", Port = port.ToString() };
udp.client = new UdpClient(int.Parse(port));
MainV2.comPort.MirrorStream = udp;
mirror.MirrorStream = udp;
udp.IsOpen = true;
CMB_baudrate.SelectedIndex = 0;
MainV2.comPort.MirrorStream.Open();
mirror.MirrorStream.Open();
mirror.MirrorStreamWrite = bool.Parse(write);
}
else if (direction == "Outbound")
{
var udp = new UdpSerialConnect() { ConfigRef = "SerialOutputPassUDPCL" };
udp.hostEndPoint = new IPEndPoint(IPAddress.Parse(extra), int.Parse(port));
udp.client = new UdpClient();
udp.IsOpen = true;
MainV2.comPort.MirrorStream = udp;
mirror.MirrorStream = udp;
mirror.MirrorStreamWrite = bool.Parse(write);
CMB_baudrate.SelectedIndex = 0;
}
}
else if (protocol == "Serial")
{
MainV2.comPort.MirrorStream = new SerialPort();
MainV2.comPort.MirrorStream.PortName = port;
MainV2.comPort.MirrorStream.BaudRate = int.Parse(extra);
MainV2.comPort.MirrorStream.Open();
mirror.MirrorStream = new SerialPort();
mirror.MirrorStream.PortName = port;
mirror.MirrorStream.BaudRate = int.Parse(extra);
mirror.MirrorStream.Open();
mirror.MirrorStreamWrite = bool.Parse(write);
}

MainV2.comPort.Mirrors.Add(mirror);
myDataGridView1[Go.Index, e.RowIndex].Value = "Started";
Started.Add(e.RowIndex);
}
catch (Exception ex) {
CustomMessageBox.Show("Error: " + ex.Message);
Expand Down
Loading

0 comments on commit f70ecb1

Please sign in to comment.