forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
CurrentState.cs
2744 lines (2207 loc) · 101 KB
/
CurrentState.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
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.ComponentModel;
using MissionPlanner.Utilities;
using log4net;
using MissionPlanner.Attributes;
using MissionPlanner;
using System.Collections;
using System.Linq;
using DirectShowLib;
namespace MissionPlanner
{
public class CurrentState : ICloneable
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public event EventHandler csCallBack;
public MAVState parent;
public int lastautowp = -1;
// multipliers
public static float multiplierdist = 1;
public static string DistanceUnit = "";
public static float multiplierspeed = 1;
public static string SpeedUnit = "";
public static double toDistDisplayUnit(double input)
{
return input*multiplierdist;
}
public static double toSpeedDisplayUnit(double input)
{
return input*multiplierspeed;
}
public static double fromDistDisplayUnit(double input)
{
return input/multiplierdist;
}
public static double fromSpeedDisplayUnit(double input)
{
return input/multiplierspeed;
}
// orientation - rads
[DisplayText("Roll (deg)")]
public float roll { get; set; }
[DisplayText("Pitch (deg)")]
public float pitch { get; set; }
[DisplayText("Yaw (deg)")]
public float yaw
{
get { return _yaw; }
set
{
if (value < 0)
{
_yaw = value + 360;
}
else
{
_yaw = value;
}
}
}
private float _yaw = 0;
[DisplayText("SSA (deg)")]
public float SSA { get; set; }
[DisplayText("AOA (deg)")]
public float AOA { get; set; }
[DisplayText("GroundCourse (deg)")]
public float groundcourse
{
get { return _groundcourse; }
set
{
if (value < 0)
{
_groundcourse = value + 360;
}
else
{
_groundcourse = value;
}
}
}
private float _groundcourse = 0;
// position
[DisplayText("Latitude")]
public double lat { get; set; }
[DisplayText("Longitude")]
public double lng { get; set; }
[DisplayText("Altitude (dist)")]
public float alt
{
get { return (_alt - altoffsethome)*multiplierdist; }
set
{
// check update rate, and ensure time hasnt gone backwards
_alt = value;
if ((datetime - lastalt).TotalSeconds >= 0.2 && oldalt != alt || lastalt > datetime)
{
climbrate = (alt - oldalt)/(float) (datetime - lastalt).TotalSeconds;
verticalspeed = (alt - oldalt)/(float) (datetime - lastalt).TotalSeconds;
if (float.IsInfinity(_verticalspeed))
_verticalspeed = 0;
lastalt = datetime;
oldalt = alt;
}
}
}
DateTime lastalt = DateTime.MinValue;
[DisplayText("Altitude (dist)")]
public float altasl
{
get { return _altasl*multiplierdist; }
set { _altasl = value; }
}
float _altasl = 0;
float oldalt = 0;
[DisplayText("Velocity X (ms)")]
public double vx { get; set; }
[DisplayText("Velocity Y (ms)")]
public double vy { get; set; }
[DisplayText("Velocity Z (ms)")]
public double vz { get; set; }
public double vlen
{
get { return Math.Sqrt(Math.Pow(vx, 2) + Math.Pow(vy, 2) + Math.Pow(vz, 2)); }
}
[DisplayText("Alt Home Offset (dist)")]
public float altoffsethome { get; set; }
private float _alt = 0;
[DisplayText("Gps Status")]
public float gpsstatus { get; set; }
[DisplayText("Gps HDOP")]
public float gpshdop { get; set; }
[DisplayText("Sat Count")]
public float satcount { get; set; }
[DisplayText("Latitude2 (dd)")]
public double lat2 { get; set; }
[DisplayText("Longitude2 (dd)")]
public double lng2 { get; set; }
[DisplayText("Altitude2 (dist)")]
public float altasl2 { get; set; }
[DisplayText("Gps Status2")]
public float gpsstatus2 { get; set; }
[DisplayText("Gps HDOP2")]
public float gpshdop2 { get; set; }
[DisplayText("Sat Count2")]
public float satcount2 { get; set; }
public float groundspeed2 { get; set; }
[DisplayText("GroundCourse2 (deg)")]
public float groundcourse2 { get; set; }
[DisplayText("Sat Count Blend")]
public float satcountB { get { return satcount + satcount2; } }
public DateTime gpstime { get; set; }
public float altd1000
{
get { return (alt/1000)%10; }
}
public float altd100
{
get { return (alt/100)%10; }
}
// speeds
[DisplayText("AirSpeed (speed)")]
public float airspeed
{
get { return _airspeed*multiplierspeed; }
set { _airspeed = value; }
}
[DisplayText("Airspeed Target (speed)")]
public float targetairspeed
{
get { return _targetairspeed; }
}
public bool lowairspeed { get; set; }
[DisplayText("Airspeed Ratio")]
public float asratio { get; set; }
[DisplayText("GroundSpeed (speed)")]
public float groundspeed
{
get { return _groundspeed*multiplierspeed; }
set { _groundspeed = value; }
}
// accel
[DisplayText("Accel X")]
public float ax { get; set; }
[DisplayText("Accel Y")]
public float ay { get; set; }
[DisplayText("Accel Z")]
public float az { get; set; }
[DisplayText("Accel Strength")]
public float accelsq
{
get { return (float)Math.Sqrt(Math.Pow(ax, 2) + Math.Pow(ay, 2) + Math.Pow(az, 2)) / 1000.0f /*980.665f*/; }
}
// gyro
[DisplayText("Gyro X")]
public float gx { get; set; }
[DisplayText("Gyro Y")]
public float gy { get; set; }
[DisplayText("Gyro Z")]
public float gz { get; set; }
[DisplayText("Gyro Strength")]
public float gyrosq
{
get { return (float)Math.Sqrt(Math.Pow(gx, 2) + Math.Pow(gy, 2) + Math.Pow(gz, 2)); }
}
// mag
[DisplayText("Mag X")]
public float mx { get; set; }
[DisplayText("Mag Y")]
public float my { get; set; }
[DisplayText("Mag Z")]
public float mz { get; set; }
[DisplayText("Mag Field")]
public float magfield
{
get { return (float) Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2)); }
}
// accel2
[DisplayText("Accel2 X")]
public float ax2 { get; set; }
[DisplayText("Accel2 Y")]
public float ay2 { get; set; }
[DisplayText("Accel2 Z")]
public float az2 { get; set; }
[DisplayText("Accel Strength2")]
public float accelsq2
{
get { return (float)Math.Sqrt(Math.Pow(ax2, 2) + Math.Pow(ay2, 2) + Math.Pow(az2, 2)) / 1000.0f /*980.665f*/; }
}
// gyro2
[DisplayText("Gyro2 X")]
public float gx2 { get; set; }
[DisplayText("Gyro2 Y")]
public float gy2 { get; set; }
[DisplayText("Gyro2 Z")]
public float gz2 { get; set; }
[DisplayText("Gyro Strength2")]
public float gyrosq2
{
get { return (float)Math.Sqrt(Math.Pow(gx2, 2) + Math.Pow(gy2, 2) + Math.Pow(gz2, 2)); }
}
// mag2
[DisplayText("Mag2 X")]
public float mx2 { get; set; }
[DisplayText("Mag2 Y")]
public float my2 { get; set; }
[DisplayText("Mag2 Z")]
public float mz2 { get; set; }
[DisplayText("Mag Field2")]
public float magfield2
{
get { return (float)Math.Sqrt(Math.Pow(mx2, 2) + Math.Pow(my2, 2) + Math.Pow(mz2, 2)); }
}
// accel3
[DisplayText("Accel3 X")]
public float ax3 { get; set; }
[DisplayText("Accel3 Y")]
public float ay3 { get; set; }
[DisplayText("Accel3 Z")]
public float az3 { get; set; }
[DisplayText("Accel Strength3")]
public float accelsq3
{
get { return (float)Math.Sqrt(Math.Pow(ax3, 2) + Math.Pow(ay3, 2) + Math.Pow(az3, 2)) / 1000.0f /*980.665f*/; }
}
// gyro3
[DisplayText("Gyro3 X")]
public float gx3 { get; set; }
[DisplayText("Gyro3 Y")]
public float gy3 { get; set; }
[DisplayText("Gyro3 Z")]
public float gz3 { get; set; }
[DisplayText("Gyro Strength3")]
public float gyrosq3
{
get { return (float)Math.Sqrt(Math.Pow(gx3, 2) + Math.Pow(gy3, 2) + Math.Pow(gz3, 2)); }
}
// mag3
[DisplayText("Mag3 X")]
public float mx3 { get; set; }
[DisplayText("Mag3 Y")]
public float my3 { get; set; }
[DisplayText("Mag3 Z")]
public float mz3 { get; set; }
[DisplayText("Mag Field3")]
public float magfield3
{
get { return (float)Math.Sqrt(Math.Pow(mx3, 2) + Math.Pow(my3, 2) + Math.Pow(mz3, 2)); }
}
//radio
public float ch1in { get; set; }
public float ch2in { get; set; }
public float ch3in { get; set; }
public float ch4in { get; set; }
public float ch5in { get; set; }
public float ch6in { get; set; }
public float ch7in { get; set; }
public float ch8in { get; set; }
public float ch9in { get; set; }
public float ch10in { get; set; }
public float ch11in { get; set; }
public float ch12in { get; set; }
public float ch13in { get; set; }
public float ch14in { get; set; }
public float ch15in { get; set; }
public float ch16in { get; set; }
// motors
public float ch1out { get; set; }
public float ch2out { get; set; }
public float ch3out { get; set; }
public float ch4out { get; set; }
public float ch5out { get; set; }
public float ch6out { get; set; }
public float ch7out { get; set; }
public float ch8out { get; set; }
public float ch9out { get; set; }
public float ch10out { get; set; }
public float ch11out { get; set; }
public float ch12out { get; set; }
public float ch13out { get; set; }
public float ch14out { get; set; }
public float ch15out { get; set; }
public float ch16out { get; set; }
public float ch3percent
{
get
{
if (_ch3percent != -1)
return _ch3percent;
try
{
if (MainV2.comPort.MAV.param.ContainsKey("RC3_MIN") &&
MainV2.comPort.MAV.param.ContainsKey("RC3_MAX"))
{
return
(int)
(((ch3out - MainV2.comPort.MAV.param["RC3_MIN"].Value)/
(MainV2.comPort.MAV.param["RC3_MAX"].Value - MainV2.comPort.MAV.param["RC3_MIN"].Value))*
100);
}
else
{
if (ch3out == 0)
return 0;
return (int) ((ch3out - 1100)/(1900 - 1100)*100);
}
}
catch
{
return 0;
}
}
set { _ch3percent = value; }
}
[DisplayText("Failsafe")]
public bool failsafe { get; set; }
[DisplayText("RX Rssi")]
public int rxrssi { get; set; }
float _ch3percent = -1;
public float crit_AOA
{
get
{
try
{
if (MainV2.comPort.MAV.param.ContainsKey("AOA_CRIT"))
{
return
(int)
(MainV2.comPort.MAV.param["AOA_CRIT"].Value);
}
else
{
return 25;
}
}
catch
{
return 0;
}
}
set { _crit_aoa = value; }
}
float _crit_aoa = 25;
public bool lowgroundspeed { get; set; }
float _airspeed;
float _groundspeed;
float _verticalspeed;
[DisplayText("Vertical Speed (speed)")]
public float verticalspeed
{
get
{
if (float.IsNaN(_verticalspeed)) _verticalspeed = 0;
return _verticalspeed*multiplierspeed;
}
set { _verticalspeed = _verticalspeed*0.4f + value*0.6f; }
}
//nav state
[DisplayText("Roll Target (deg)")]
public float nav_roll { get; set; }
[DisplayText("Pitch Target (deg)")]
public float nav_pitch { get; set; }
[DisplayText("Bearing Target (deg)")]
public float nav_bearing { get; set; }
[DisplayText("Bearing Target (deg)")]
public float target_bearing { get; set; }
[DisplayText("Dist to WP (dist)")]
public float wp_dist
{
get { return (_wpdist*multiplierdist); }
set { _wpdist = value; }
}
[DisplayText("Altitude Error (dist)")]
public float alt_error
{
get { return _alt_error*multiplierdist; }
set
{
if (_alt_error == value) return;
_alt_error = value;
_targetalt = _targetalt*0.5f + (float) Math.Round(alt + alt_error, 0)*0.5f;
}
}
[DisplayText("Bearing Error (deg)")]
public float ber_error
{
get { return (target_bearing - yaw); }
set { }
}
[DisplayText("Airspeed Error (speed)")]
public float aspd_error
{
get { return _aspd_error*multiplierspeed; }
set
{
if (_aspd_error == value) return;
_aspd_error = value;
_targetairspeed = _targetairspeed*0.5f + (float) Math.Round(airspeed + aspd_error, 0)*0.5f;
}
}
[DisplayText("Xtrack Error (m)")]
public float xtrack_error { get; set; }
[DisplayText("WP No")]
public float wpno { get; set; }
[DisplayText("Mode")]
public string mode { get; set; }
uint _mode = 99999;
[DisplayText("ClimbRate (speed)")]
public float climbrate
{
get { return _climbrate*multiplierspeed; }
set { _climbrate = value; }
}
/// <summary>
/// time over target in seconds
/// </summary>
[DisplayText("Time over Target (sec)")]
public int tot
{
get
{
if (groundspeed <= 0) return 0;
return (int) (wp_dist/groundspeed);
}
}
[DisplayText("Time over Home (sec)")]
public int toh
{
get
{
if (groundspeed <= 0) return 0;
return (int) (DistToHome/groundspeed);
}
}
[DisplayText("Dist Traveled (dist)")]
public float distTraveled { get; set; }
[DisplayText("Time in Air (sec)")]
public float timeInAir { get; set; }
// calced turn rate
[DisplayText("Turn Rate (speed)")]
public float turnrate
{
get
{
if (groundspeed <= 1) return 0;
return (roll*9.8f)/groundspeed;
}
}
// turn radius
[DisplayText("Turn Radius (dist)")]
public float radius
{
get
{
if (groundspeed <= 1) return 0;
return ((groundspeed*groundspeed)/(float) (9.8f*Math.Tan(roll*MathHelper.deg2rad)));
}
}
float _wpdist;
float _aspd_error;
float _alt_error;
float _targetalt;
float _targetairspeed;
float _climbrate;
[DisplayText("Wind Direction (Deg)")]
public float wind_dir { get; set; }
[DisplayText("Wind Velocity (speed)")]
public float wind_vel { get; set; }
/// <summary>
/// used in wind calc
/// </summary>
double Wn_fgo;
/// <summary>
/// used for wind calc
/// </summary>
double We_fgo;
public float targetaltd100
{
get { return (_targetalt/100)%10; }
}
public float targetalt
{
get { return _targetalt; }
}
//airspeed_error = (airspeed_error - airspeed);
//message
public List<string> messages { get; set; }
internal string message
{
get
{
if (messages.Count == 0) return "";
return messages[messages.Count - 1];
}
}
public string messageHigh
{
get { return _messagehigh; }
set { _messagehigh = value; }
}
private string _messagehigh;
public DateTime messageHighTime { get; set; }
//battery
[DisplayText("Bat Voltage (V)")]
public double battery_voltage
{
get { return _battery_voltage; }
set
{
if (_battery_voltage == 0) _battery_voltage = value;
_battery_voltage = value*0.2f + _battery_voltage*0.8f;
}
}
internal double _battery_voltage;
[DisplayText("Bat Remaining (%)")]
public int battery_remaining
{
get { return _battery_remaining; }
set
{
_battery_remaining = value;
if (_battery_remaining < 0 || _battery_remaining > 100) _battery_remaining = 0;
}
}
private int _battery_remaining;
[DisplayText("Bat Current (Amps)")]
public double current
{
get { return _current; }
set
{
if (_lastcurrent == DateTime.MinValue) _lastcurrent = datetime;
// case for no sensor
if (value == -0.01f)
{
_current = 0;
return;
}
battery_usedmah += ((value*1000.0)*(datetime - _lastcurrent).TotalHours);
_current = value;
_lastcurrent = datetime;
}
} //current may to be below zero - recuperation in arduplane
private double _current;
[DisplayText("Bat Watts")]
public double watts
{
get { return battery_voltage*current; }
}
private DateTime _lastcurrent = DateTime.MinValue;
[DisplayText("Bat efficiency (mah/km)")]
public double battery_mahperkm { get {return battery_usedmah / (distTraveled/1000.0f); } }
[DisplayText("Bat km left EST (km)")]
public double battery_kmleft { get { return (((100.0f / (100.0f - battery_remaining)) * battery_usedmah) - battery_usedmah) / battery_mahperkm; } }
[DisplayText("Bat used EST (mah)")]
public double battery_usedmah { get; set; }
public double battery_cell1 { get; set; }
public double battery_cell2 { get; set; }
public double battery_cell3 { get; set; }
public double battery_cell4 { get; set; }
public double battery_cell5 { get; set; }
public double battery_cell6 { get; set; }
public double battery_temp { get; set; }
[DisplayText("Bat2 Voltage (V)")]
public double battery_voltage2
{
get { return _battery_voltage2; }
set
{
if (_battery_voltage2 == 0) _battery_voltage2 = value;
_battery_voltage2 = value*0.2f + _battery_voltage2*0.8f;
}
}
internal double _battery_voltage2;
[DisplayText("Bat2 Current (Amps)")]
public double current2
{
get { return _current2; }
set
{
if (value < 0) return;
_current2 = value;
}
}
private double _current2;
public double HomeAlt
{
get { return HomeLocation.Alt; }
set { }
}
static PointLatLngAlt _homelocation = new PointLatLngAlt();
public PointLatLngAlt HomeLocation
{
get { return _homelocation; }
set { _homelocation = value; }
}
public PointLatLngAlt MovingBase = null;
static PointLatLngAlt _trackerloc = new PointLatLngAlt();
public PointLatLngAlt TrackerLocation
{
get
{
if (_trackerloc.Lng != 0) return _trackerloc;
return HomeLocation;
}
set { _trackerloc = value; }
}
public PointLatLngAlt Location
{
get { return new PointLatLngAlt(lat, lng, altasl); }
}
public float GeoFenceDist
{
get
{
try
{
float disttotal = 99999;
PointLatLngAlt lineStartLatLngAlt = null;
var R = 6371e3;
// close loop
var list = MainV2.comPort.MAV.fencepoints.ToList();
if (list.Count > 0)
{
// remove return location
list.RemoveAt(0);
}
// check all segments
foreach (var mavlinkFencePointT in list)
{
if (lineStartLatLngAlt == null)
{
lineStartLatLngAlt = new PointLatLngAlt(mavlinkFencePointT.Value.lat,
mavlinkFencePointT.Value.lng);
continue;
}
// crosstrack distance
var lineEndLatLngAlt = new PointLatLngAlt(mavlinkFencePointT.Value.lat, mavlinkFencePointT.Value.lng);
var lineDist = lineStartLatLngAlt.GetDistance2(lineEndLatLngAlt);
var distToLocation = lineStartLatLngAlt.GetDistance2(Location);
var bearToLocation = lineStartLatLngAlt.GetBearing(Location);
var lineBear = lineStartLatLngAlt.GetBearing(lineEndLatLngAlt);
var angle = bearToLocation - lineBear;
if (angle < 0)
angle += 360;
var alongline = Math.Cos(angle*MathHelper.deg2rad)*distToLocation;
// check to see if our point is still within the line length
if (alongline > lineDist)
{
lineStartLatLngAlt = lineEndLatLngAlt;
continue;
}
var dXt2 = Math.Sin(angle*MathHelper.deg2rad)*distToLocation;
var dXt = Math.Asin(Math.Sin(distToLocation/R)*Math.Sin(angle*MathHelper.deg2rad))*R;
disttotal = (float) Math.Min(disttotal, Math.Abs(dXt2));
lineStartLatLngAlt = lineEndLatLngAlt;
}
// check also distance from the points - because if we are outside the polygon, we may be on a corner segment
foreach (var mavlinkFencePointT in list)
{
var pathpoint = new PointLatLngAlt(mavlinkFencePointT.Value.lat, mavlinkFencePointT.Value.lng);
var dXt2 = pathpoint.GetDistance(Location);
disttotal = (float)Math.Min(disttotal, Math.Abs(dXt2));
}
return disttotal;
}
catch
{
return 0;
}
}
}
[DisplayText("Dist to Home (dist)")]
public float DistToHome
{
get
{
if (lat == 0 && lng == 0 || TrackerLocation.Lat == 0)
return 0;
// shrinking factor for longitude going to poles direction
double rads = Math.Abs(TrackerLocation.Lat)*0.0174532925;
double scaleLongDown = Math.Cos(rads);
double scaleLongUp = 1.0f/Math.Cos(rads);
//DST to Home
double dstlat = Math.Abs(TrackerLocation.Lat - lat)*111319.5;
double dstlon = Math.Abs(TrackerLocation.Lng - lng)*111319.5*scaleLongDown;
return (float) Math.Sqrt((dstlat*dstlat) + (dstlon*dstlon))*multiplierdist;
}
}
[DisplayText("Dist to Moving Base (dist)")]
public float DistFromMovingBase
{
get
{
if (lat == 0 && lng == 0 || MovingBase == null)
return 0;
// shrinking factor for longitude going to poles direction
double rads = Math.Abs(MovingBase.Lat)*0.0174532925;
double scaleLongDown = Math.Cos(rads);
double scaleLongUp = 1.0f/Math.Cos(rads);
//DST to Home
double dstlat = Math.Abs(MovingBase.Lat - lat)*111319.5;
double dstlon = Math.Abs(MovingBase.Lng - lng)*111319.5*scaleLongDown;
return (float) Math.Sqrt((dstlat*dstlat) + (dstlon*dstlon))*multiplierdist;
}
}
[DisplayText("Elevation to Mav (deg)")]
public float ELToMAV
{
get
{
float dist = DistToHome/multiplierdist;
if (dist < 5)
return 0;
float altdiff = (float) (_altasl - TrackerLocation.Alt);
float angle = (float) (Math.Atan(altdiff/dist)*MathHelper.rad2deg);
return angle;
}
}
[DisplayText("Bearing to Mav (deg)")]
public float AZToMAV
{
get
{
// shrinking factor for longitude going to poles direction
double rads = Math.Abs(TrackerLocation.Lat)*0.0174532925;
double scaleLongDown = Math.Cos(rads);
double scaleLongUp = 1.0f/Math.Cos(rads);
//DIR to Home
double dstlon = (TrackerLocation.Lng - lng); //OffSet_X
double dstlat = (TrackerLocation.Lat - lat)*scaleLongUp; //OffSet Y
double bearing = 90 + (Math.Atan2(dstlat, -dstlon)*57.295775); //absolut home direction
if (bearing < 0) bearing += 360; //normalization
//bearing = bearing - 180;//absolut return direction
//if (bearing < 0) bearing += 360;//normalization
float dist = DistToHome/multiplierdist;
if (dist < 5)
return 0;
return (float) bearing;
}
}
[DisplayText("Sonar Range (meters)")]
public float sonarrange
{
get { return (float) toDistDisplayUnit(_sonarrange); }
set { _sonarrange = value; }
}
float _sonarrange = 0;
[DisplayText("Sonar Voltage (Volt)")]
public float sonarvoltage { get; set; }
// current firmware
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduCopter2;
public float freemem { get; set; }
public float load { get; set; }
public float brklevel { get; set; }
public bool armed { get; set; }
// Sik radio
[DisplayText("Sik Radio rssi")]
public float rssi { get; set; }
[DisplayText("Sik Radio remote rssi")]
public float remrssi { get; set; }
public byte txbuffer { get; set; }
[DisplayText("Sik Radio noise")]
public float noise { get; set; }
[DisplayText("Sik Radio remote noise")]