forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
OpenGLtest.cs
382 lines (273 loc) · 13.5 KB
/
OpenGLtest.cs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using OpenTK;
using OpenTK.Graphics.OpenGL;
using System.Drawing.Imaging;
using System.Drawing;
using GMap.NET;
using GMap.NET.WindowsForms;
using MissionPlanner.Utilities;
using GMap.NET.MapProviders;
namespace MissionPlanner.Controls
{
public class OpenGLtest : GLControl
{
public static OpenGLtest instance;
// terrain image
Bitmap _terrain = new Bitmap(640,480);
int texture = 0;
float _angle = 0;
double cameraX, cameraY, cameraZ; // camera coordinates
double lookX, lookY, lookZ; // camera look-at coordinates
double step = 1 / 1200.0;
// image zoom level
int zoom = 14;
RectLatLng area = new RectLatLng(-35.04286,117.84262,0.1,0.1);
double _alt = 0;
public PointLatLngAlt LocationCenter {
get {
return new PointLatLngAlt(area.LocationMiddle.Lat, area.LocationMiddle.Lng,_alt,"");
}
set {
if (area.LocationMiddle.Lat == value.Lat && area.LocationMiddle.Lng == value.Lng)
return;
if (value.Lat == 0 && value.Lng == 0)
return;
_alt = value.Alt;
area = new RectLatLng(value.Lat + 0.15, value.Lng - 0.15, 0.3, 0.3);
// Console.WriteLine(area.LocationMiddle + " " + value.ToString());
this.Invalidate();
}
}
public Vector3 rpy = new Vector3();
public OpenGLtest()
{
instance = this;
InitializeComponent();
}
void getImage()
{
GMapProvider type = GMap.NET.MapProviders.GoogleSatelliteMapProvider.Instance;
PureProjection prj = type.Projection;
if (!area.IsEmpty)
{
try
{
List<GPoint> tileArea = prj.GetAreaTileList(area, zoom, 0);
//string bigImage = zoom + "-" + type + "-vilnius.png";
//Console.WriteLine("Preparing: " + bigImage);
//Console.WriteLine("Zoom: " + zoom);
//Console.WriteLine("Type: " + type.ToString());
//Console.WriteLine("Area: " + area);
var types = type;// GMaps.Instance.GetAllLayersOfType(type);
// current area
GPoint topLeftPx = prj.FromLatLngToPixel(area.LocationTopLeft, zoom);
GPoint rightButtomPx = prj.FromLatLngToPixel(area.Bottom, area.Right, zoom);
GPoint pxDelta = new GPoint(rightButtomPx.X - topLeftPx.X, rightButtomPx.Y - topLeftPx.Y);
DateTime startimage = DateTime.Now;
int padding = 0;
{
using (Bitmap bmpDestination = new Bitmap((int)pxDelta.X + padding * 2, (int)pxDelta.Y + padding * 2))
{
using (Graphics gfx = Graphics.FromImage(bmpDestination))
{
gfx.CompositingMode = System.Drawing.Drawing2D.CompositingMode.SourceOver;
// get tiles & combine into one
foreach (var p in tileArea)
{
Console.WriteLine("Downloading[" + p + "]: " + tileArea.IndexOf(p) + " of " + tileArea.Count);
//foreach (GMapProvider tp in types)
{
GMapImage tile = type.GetTileImage(p, zoom) as GMapImage;
if (tile != null)
{
using (tile)
{
long x = p.X * prj.TileSize.Width - topLeftPx.X + padding;
long y = p.Y * prj.TileSize.Width - topLeftPx.Y + padding;
{
gfx.DrawImage(tile.Img, x, y, prj.TileSize.Width, prj.TileSize.Height);
}
}
}
}
if ((DateTime.Now - startimage).TotalMilliseconds > 200)
break;
}
}
_terrain = new Bitmap(bmpDestination, 512, 512);
GL.BindTexture(TextureTarget.Texture2D, texture);
BitmapData data = _terrain.LockBits(new System.Drawing.Rectangle(0, 0, _terrain.Width, _terrain.Height),
ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb);
//Console.WriteLine("w {0} h {1}",data.Width, data.Height);
GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0,
OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0);
_terrain.UnlockBits(data);
GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear);
GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear);
}
}
if ((DateTime.Now - startimage).TotalMilliseconds > 200)
{
zoom--;
}
else
{
//zoom++;
}
}
catch { }
}
}
const float rad2deg = (float)(180 / Math.PI);
const float deg2rad = (float)(1.0 / rad2deg);
public Vector3 Normal(Vector3 a, Vector3 b, Vector3 c)
{
var dir = Vector3.Cross(b - a, c - a);
var norm = Vector3.Normalize(dir);
return norm;
}
protected override void OnPaint(System.Windows.Forms.PaintEventArgs e)
{
if (this.DesignMode)
return;
if (area.LocationMiddle.Lat == 0 && area.LocationMiddle.Lng == 0)
return;
_angle+=1f;
// area.LocationTopLeft = new PointLatLng(area.LocationTopLeft.Lat + 0.0001,area.LocationTopLeft.Lng);
//area.Size = new SizeLatLng(0.1, 0.1);
try
{
base.OnPaint(e);
}
catch { return; }
double heightscale = (step / 90.0) * 1;
float scale = 1.0f;
float radians = (float)(Math.PI * (rpy.Z * -1) / 180.0f);
//radians = 0;
float mouseY = (float)(0.1 * scale);
cameraX = area.LocationMiddle.Lng; // multiplying by mouseY makes the
cameraZ = area.LocationMiddle.Lat; // camera get closer/farther away with mouseY
cameraY = (LocationCenter.Alt < srtm.getAltitude(cameraZ, cameraX, 20)) ? (srtm.getAltitude(cameraZ, cameraX, 20)+ 0.2) * heightscale : LocationCenter.Alt * heightscale;// (srtm.getAltitude(lookZ, lookX, 20) + 100) * heighscale;
lookX = area.LocationMiddle.Lng + Math.Sin(radians) * mouseY; ;
lookY = cameraY;
lookZ = area.LocationMiddle.Lat + Math.Cos(radians) * mouseY; ;
MakeCurrent();
GL.MatrixMode(MatrixMode.Projection);
OpenTK.Matrix4 projection = OpenTK.Matrix4.CreatePerspectiveFieldOfView(60 * deg2rad, 1f, 0.00001f, 5000.0f);
GL.LoadMatrix(ref projection);
Matrix4 modelview = Matrix4.LookAt((float)cameraX, (float)cameraY, (float)cameraZ, (float)lookX, (float)lookY, (float)lookZ, 0,1,0);
GL.MatrixMode(MatrixMode.Modelview);
// roll
modelview = Matrix4.Mult(modelview,Matrix4.CreateRotationZ (rpy.X * deg2rad));
// pitch
modelview = Matrix4.Mult(modelview, Matrix4.CreateRotationX(rpy.Y * -deg2rad));
GL.LoadMatrix(ref modelview);
GL.ClearColor(Color.Blue);
GL.Clear(ClearBufferMask.ColorBufferBit | ClearBufferMask.DepthBufferBit);
GL.LightModel(LightModelParameter.LightModelAmbient,new float[] {1f,1f,1f,1f});
GL.Enable(EnableCap.Texture2D);
GL.BindTexture(TextureTarget.Texture2D, texture);
/*
GL.Begin(BeginMode.LineStrip);
GL.Color3(Color.White);
GL.Vertex3(0, 0, 0);
GL.Vertex3(area.Bottom, 0, area.Left);
GL.Vertex3(lookX, lookY, lookZ);
//GL.Vertex3(cameraX, cameraY, cameraZ);
GL.End();
*/
System.Diagnostics.Stopwatch sw = new System.Diagnostics.Stopwatch();
sw.Start();
zoom = 14;
getImage();
sw.Stop();
Console.WriteLine("img " +sw.ElapsedMilliseconds);
sw.Start();
double increment = step *5;
double cleanup = area.Bottom % increment;
double cleanup2 = area.Left % increment;
for (double z = (area.Bottom - cleanup); z < area.Top - step; z += increment)
{
//Makes OpenGL draw a triangle at every three consecutive vertices
GL.Begin(PrimitiveType.TriangleStrip);
for (double x = (area.Left - cleanup2); x < area.Right - step; x += increment)
{
double heightl = srtm.getAltitude(z, area.Right + area.Left - x, 20);
// Console.WriteLine(x + " " + z);
GL.Color3(Color.White);
// int heightl = 0;
double scale2 = (Math.Abs(x - area.Left) / area.WidthLng);// / (float)_terrain.Width;
double scale3 = (Math.Abs(z - area.Bottom) / area.HeightLat);// / (float)_terrain.Height;
double imgx = 1 - scale2;
double imgy = 1 - scale3;
// GL.Color3(Color.Red);
//GL.Color3(_terrain.GetPixel(imgx, imgy));
GL.TexCoord2(imgx,imgy);
GL.Vertex3(x, heightl * heightscale, z); // _terrain.GetPixel(x, z).R
try
{
heightl = srtm.getAltitude(z + increment, area.Right + area.Left - x, 20);
//scale2 = (Math.Abs(x - area.Left) / area.WidthLng) * (float)_terrain.Width;
scale3 = (Math.Abs(((z + increment) - area.Bottom)) / area.HeightLat);// / (float)_terrain.Height;
imgx = 1- scale2;
imgy = 1 - scale3;
// GL.Color3(Color.Green);
//GL.Color3(_terrain.GetPixel(imgx, imgy));
GL.TexCoord2(imgx,imgy);
GL.Vertex3(x, heightl * heightscale, z + increment);
// Console.WriteLine(x + " " + (z + step));
}
catch { break; }
}
GL.End();
}
GL.Enable(EnableCap.Blend);
GL.DepthMask(false);
GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.One);
GL.DepthMask(true);
GL.Disable(EnableCap.Blend);
GL.Flush();
sw.Stop();
Console.WriteLine("GL "+sw.ElapsedMilliseconds);
this.SwapBuffers();
Context.MakeCurrent(null);
//this.Invalidate();
}
private void InitializeComponent()
{
this.SuspendLayout();
//
// OpenGLtest
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.Name = "OpenGLtest";
this.Load += new System.EventHandler(this.test_Load);
this.Resize += new System.EventHandler(this.test_Resize);
this.ResumeLayout(false);
}
private void test_Load(object sender, EventArgs e)
{
GL.GenTextures(1, out texture);
GL.Enable(EnableCap.DepthTest);
// GL.Enable(EnableCap.Light0);
GL.Enable(EnableCap.Lighting);
GL.Enable(EnableCap.ColorMaterial);
GL.Enable(EnableCap.Normalize);
//GL.Enable(EnableCap.LineSmooth);
//GL.Enable(EnableCap.PointSmooth);
//GL.Enable(EnableCap.PolygonSmooth);
GL.ShadeModel(ShadingModel.Smooth);
GL.Enable(EnableCap.CullFace);
GL.Enable(EnableCap.Texture2D);
}
private void test_Resize(object sender, EventArgs e)
{
MakeCurrent();
GL.Viewport(0, 0, this.Width, this.Height);
this.Invalidate();
}
}
}