aboutsummaryrefslogtreecommitdiff
path: root/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
blob: 5d768b73ddc8e8c0277ffb1669f9e857451c3c48 (plain) (blame)
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
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
1421
1422
1423
1424
1425
1426
1427
1428
1429
1430
1431
1432
1433
1434
1435
1436
1437
1438
1439
1440
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
1481
1482
1483
1484
1485
1486
1487
1488
1489
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
1518
1519
1520
1521
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
1544
1545
1546
1547
1548
1549
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
1563
1564
1565
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
1608
1609
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
1684
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
1719
1720
1721
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
/****************************************************************************
 *
 *   Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/**
 * @file ekf_att_pos_estimator_main.cpp
 * Implementation of the attitude and position estimator.
 *
 * @author Paul Riseborough <p_riseborough@live.com.au>
 * @author Lorenz Meier <lm@inf.ethz.ch>
 */

#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <math.h>
#include <poll.h>
#include <time.h>
#include <float.h>

#define SENSOR_COMBINED_SUB

#include <drivers/drv_hrt.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_baro.h>
#ifdef SENSOR_COMBINED_SUB
#include <uORB/topics/sensor_combined.h>
#endif
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/estimator_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/wind_estimate.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>

#include "estimator_23states.h"



/**
 * estimator app start / stop handling function
 *
 * @ingroup apps
 */
extern "C" __EXPORT int ekf_att_pos_estimator_main(int argc, char *argv[]);

__EXPORT uint32_t millis();

static uint64_t IMUmsec = 0;
static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000;

uint32_t millis()
{
	return IMUmsec;
}

class FixedwingEstimator
{
public:
	/**
	 * Constructor
	 */
	FixedwingEstimator();

	/**
	 * Destructor, also kills the sensors task.
	 */
	~FixedwingEstimator();

	/**
	 * Start the sensors task.
	 *
	 * @return	OK on success.
	 */
	int		start();

	/**
	 * Print the current status.
	 */
	void		print_status();

	/**
	 * Trip the filter by feeding it NaN values.
	 */
	int		trip_nan();

	/**
	 * Enable logging.
	 *
	 * @param	enable Set to true to enable logging, false to disable
	 */
	int		enable_logging(bool enable);

	/**
	 * Set debug level.
	 *
	 * @param	debug Desired debug level - 0 to disable.
	 */
	int		set_debuglevel(unsigned debug) { _debug = debug; return 0; }

private:

	bool		_task_should_exit;		/**< if true, sensor task should exit */
	int		_estimator_task;			/**< task handle for sensor task */
#ifndef SENSOR_COMBINED_SUB
	int		_gyro_sub;			/**< gyro sensor subscription */
	int		_accel_sub;			/**< accel sensor subscription */
	int		_mag_sub;			/**< mag sensor subscription */
#else
	int		_sensor_combined_sub;
#endif
	int		_airspeed_sub;			/**< airspeed subscription */
	int		_baro_sub;			/**< barometer subscription */
	int		_gps_sub;			/**< GPS subscription */
	int		_vstatus_sub;			/**< vehicle status subscription */
	int 		_params_sub;			/**< notification of parameter updates */
	int 		_manual_control_sub;		/**< notification of manual control updates */
	int		_mission_sub;
	int		_home_sub;			/**< home position as defined by commander / user */

	orb_advert_t	_att_pub;			/**< vehicle attitude */
	orb_advert_t	_global_pos_pub;		/**< global position */
	orb_advert_t	_local_pos_pub;			/**< position in local frame */
	orb_advert_t	_estimator_status_pub;		/**< status of the estimator */
	orb_advert_t	_wind_pub;			/**< wind estimate */

	struct vehicle_attitude_s			_att;			/**< vehicle attitude */
	struct gyro_report				_gyro;
	struct accel_report				_accel;
	struct mag_report				_mag;
	struct airspeed_s				_airspeed;		/**< airspeed */
	struct baro_report				_baro;			/**< baro readings */
	struct vehicle_status_s				_vstatus;		/**< vehicle status */
	struct vehicle_global_position_s		_global_pos;		/**< global vehicle position */
	struct vehicle_local_position_s			_local_pos;		/**< local vehicle position */
	struct vehicle_gps_position_s			_gps;			/**< GPS position */
	struct wind_estimate_s				_wind;			/**< Wind estimate */

	struct gyro_scale				_gyro_offsets;
	struct accel_scale				_accel_offsets;
	struct mag_scale				_mag_offsets;

#ifdef SENSOR_COMBINED_SUB
	struct sensor_combined_s			_sensor_combined;
#endif

	struct map_projection_reference_s	_pos_ref;

	float						_baro_ref;		/**< barometer reference altitude */
	float						_baro_ref_offset;	/**< offset between initial baro reference and GPS init baro altitude */
	float						_baro_gps_offset;	/**< offset between baro altitude (at GPS init time) and GPS altitude */

	perf_counter_t	_loop_perf;			///< loop performance counter
	perf_counter_t	_perf_gyro;			///<local performance counter for gyro updates
	perf_counter_t	_perf_mag;			///<local performance counter for mag updates
	perf_counter_t	_perf_gps;			///<local performance counter for gps updates
	perf_counter_t	_perf_baro;			///<local performance counter for baro updates
	perf_counter_t	_perf_airspeed;			///<local performance counter for airspeed updates
	perf_counter_t	_perf_reset;			///<local performance counter for filter resets

	bool						_baro_init;
	bool						_gps_initialized;
	hrt_abstime					_gps_start_time;
	hrt_abstime					_filter_start_time;
	hrt_abstime					_last_sensor_timestamp;
	hrt_abstime					_last_run;
	bool						_gyro_valid;
	bool						_accel_valid;
	bool						_mag_valid;
	bool						_ekf_logging;		///< log EKF state
	unsigned					_debug;			///< debug level - default 0

	int						_mavlink_fd;

	struct {
		int32_t	vel_delay_ms;
		int32_t	pos_delay_ms;
		int32_t	height_delay_ms;
		int32_t	mag_delay_ms;
		int32_t	tas_delay_ms;
		float velne_noise;
		float veld_noise;
		float posne_noise;
		float posd_noise;
		float mag_noise;
		float gyro_pnoise;
		float acc_pnoise;
		float gbias_pnoise;
		float abias_pnoise;
		float mage_pnoise;
		float magb_pnoise;
		float eas_noise;
		float pos_stddev_threshold;
	}		_parameters;			/**< local copies of interesting parameters */

	struct {
		param_t vel_delay_ms;
		param_t	pos_delay_ms;
		param_t	height_delay_ms;
		param_t	mag_delay_ms;
		param_t	tas_delay_ms;
		param_t velne_noise;
		param_t veld_noise;
		param_t posne_noise;
		param_t posd_noise;
		param_t mag_noise;
		param_t gyro_pnoise;
		param_t acc_pnoise;
		param_t gbias_pnoise;
		param_t abias_pnoise;
		param_t mage_pnoise;
		param_t magb_pnoise;
		param_t eas_noise;
		param_t pos_stddev_threshold;
	}		_parameter_handles;		/**< handles for interesting parameters */

	AttPosEKF					*_ekf;

	float						_velocity_xy_filtered;
	float						_velocity_z_filtered;
	float						_airspeed_filtered;

	/**
	 * Update our local parameter cache.
	 */
	int		parameters_update();

	/**
	 * Update control outputs
	 *
	 */
	void		control_update();

	/**
	 * Check for changes in vehicle status.
	 */
	void		vehicle_status_poll();

	/**
	 * Shim for calling task_main from task_create.
	 */
	static void	task_main_trampoline(int argc, char *argv[]);

	/**
	 * Main filter task.
	 */
	void		task_main();

	/**
	 * Check filter sanity state
	 *
	 * @return zero if ok, non-zero for a filter error condition.
	 */
	int		check_filter_state();
};

namespace estimator
{

/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
#endif
static const int ERROR = -1;

FixedwingEstimator	*g_estimator;
}

FixedwingEstimator::FixedwingEstimator() :

	_task_should_exit(false),
	_estimator_task(-1),

/* subscriptions */
#ifndef SENSOR_COMBINED_SUB
	_gyro_sub(-1),
	_accel_sub(-1),
	_mag_sub(-1),
#else
	_sensor_combined_sub(-1),
#endif
	_airspeed_sub(-1),
	_baro_sub(-1),
	_gps_sub(-1),
	_vstatus_sub(-1),
	_params_sub(-1),
	_manual_control_sub(-1),
	_mission_sub(-1),
	_home_sub(-1),

/* publications */
	_att_pub(-1),
	_global_pos_pub(-1),
	_local_pos_pub(-1),
	_estimator_status_pub(-1),
	_wind_pub(-1),

	_att({}),
	_gyro({}),
	_accel({}),
	_mag({}),
	_airspeed({}),
	_baro({}),
	_vstatus({}),
	_global_pos({}),
	_local_pos({}),
	_gps({}),
	_wind({}),

	_gyro_offsets({}),
	_accel_offsets({}),
	_mag_offsets({}),

	#ifdef SENSOR_COMBINED_SUB
	_sensor_combined({}),
	#endif

	_baro_ref(0.0f),
	_baro_ref_offset(0.0f),
	_baro_gps_offset(0.0f),

/* performance counters */
	_loop_perf(perf_alloc(PC_ELAPSED, "ekf_att_pos_estimator")),
	_perf_gyro(perf_alloc(PC_INTERVAL, "ekf_att_pos_gyro_upd")),
	_perf_mag(perf_alloc(PC_INTERVAL, "ekf_att_pos_mag_upd")),
	_perf_gps(perf_alloc(PC_INTERVAL, "ekf_att_pos_gps_upd")),
	_perf_baro(perf_alloc(PC_INTERVAL, "ekf_att_pos_baro_upd")),
	_perf_airspeed(perf_alloc(PC_INTERVAL, "ekf_att_pos_aspd_upd")),
	_perf_reset(perf_alloc(PC_COUNT, "ekf_att_pos_reset")),

/* states */
	_baro_init(false),
	_gps_initialized(false),
	_gyro_valid(false),
	_accel_valid(false),
	_mag_valid(false),
	_ekf_logging(true),
	_debug(0),
	_mavlink_fd(-1),
	_ekf(nullptr),
	_velocity_xy_filtered(0.0f),
	_velocity_z_filtered(0.0f),
	_airspeed_filtered(0.0f)
{

	_last_run = hrt_absolute_time();

	_parameter_handles.vel_delay_ms = param_find("PE_VEL_DELAY_MS");
	_parameter_handles.pos_delay_ms = param_find("PE_POS_DELAY_MS");
	_parameter_handles.height_delay_ms = param_find("PE_HGT_DELAY_MS");
	_parameter_handles.mag_delay_ms = param_find("PE_MAG_DELAY_MS");
	_parameter_handles.tas_delay_ms = param_find("PE_TAS_DELAY_MS");
	_parameter_handles.velne_noise = param_find("PE_VELNE_NOISE");
	_parameter_handles.veld_noise = param_find("PE_VELD_NOISE");
	_parameter_handles.posne_noise = param_find("PE_POSNE_NOISE");
	_parameter_handles.posd_noise = param_find("PE_POSD_NOISE");
	_parameter_handles.mag_noise = param_find("PE_MAG_NOISE");
	_parameter_handles.gyro_pnoise = param_find("PE_GYRO_PNOISE");
	_parameter_handles.acc_pnoise = param_find("PE_ACC_PNOISE");
	_parameter_handles.gbias_pnoise = param_find("PE_GBIAS_PNOISE");
	_parameter_handles.abias_pnoise = param_find("PE_ABIAS_PNOISE");
	_parameter_handles.mage_pnoise = param_find("PE_MAGE_PNOISE");
	_parameter_handles.magb_pnoise = param_find("PE_MAGB_PNOISE");
	_parameter_handles.eas_noise = param_find("PE_EAS_NOISE");
	_parameter_handles.pos_stddev_threshold = param_find("PE_POSDEV_INIT");

	/* fetch initial parameter values */
	parameters_update();

	/* get offsets */

	int fd, res;

	fd = open(GYRO_DEVICE_PATH, O_RDONLY);

	if (fd > 0) {
		res = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&_gyro_offsets);
		close(fd);

		if (res) {
			warnx("G SCALE FAIL");
		}
	}

	fd = open(ACCEL_DEVICE_PATH, O_RDONLY);

	if (fd > 0) {
		res = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&_accel_offsets);
		close(fd);

		if (res) {
			warnx("A SCALE FAIL");
		}
	}

	fd = open(MAG_DEVICE_PATH, O_RDONLY);

	if (fd > 0) {
		res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&_mag_offsets);
		close(fd);

		if (res) {
			warnx("M SCALE FAIL");
		}
	}
}

FixedwingEstimator::~FixedwingEstimator()
{
	if (_estimator_task != -1) {

		/* task wakes up every 100ms or so at the longest */
		_task_should_exit = true;

		/* wait for a second for the task to quit at our request */
		unsigned i = 0;

		do {
			/* wait 20ms */
			usleep(20000);

			/* if we have given up, kill it */
			if (++i > 50) {
				task_delete(_estimator_task);
				break;
			}
		} while (_estimator_task != -1);
	}

	delete _ekf;

	estimator::g_estimator = nullptr;
}

int
FixedwingEstimator::enable_logging(bool logging)
{
	_ekf_logging = logging;

	return 0;
}

int
FixedwingEstimator::parameters_update()
{

	param_get(_parameter_handles.vel_delay_ms, &(_parameters.vel_delay_ms));
	param_get(_parameter_handles.pos_delay_ms, &(_parameters.pos_delay_ms));
	param_get(_parameter_handles.height_delay_ms, &(_parameters.height_delay_ms));
	param_get(_parameter_handles.mag_delay_ms, &(_parameters.mag_delay_ms));
	param_get(_parameter_handles.tas_delay_ms, &(_parameters.tas_delay_ms));
	param_get(_parameter_handles.velne_noise, &(_parameters.velne_noise));
	param_get(_parameter_handles.veld_noise, &(_parameters.veld_noise));
	param_get(_parameter_handles.posne_noise, &(_parameters.posne_noise));
	param_get(_parameter_handles.posd_noise, &(_parameters.posd_noise));
	param_get(_parameter_handles.mag_noise, &(_parameters.mag_noise));
	param_get(_parameter_handles.gyro_pnoise, &(_parameters.gyro_pnoise));
	param_get(_parameter_handles.acc_pnoise, &(_parameters.acc_pnoise));
	param_get(_parameter_handles.gbias_pnoise, &(_parameters.gbias_pnoise));
	param_get(_parameter_handles.abias_pnoise, &(_parameters.abias_pnoise));
	param_get(_parameter_handles.mage_pnoise, &(_parameters.mage_pnoise));
	param_get(_parameter_handles.magb_pnoise, &(_parameters.magb_pnoise));
	param_get(_parameter_handles.eas_noise, &(_parameters.eas_noise));
	param_get(_parameter_handles.pos_stddev_threshold, &(_parameters.pos_stddev_threshold));

	if (_ekf) {
		// _ekf->yawVarScale = 1.0f;
		// _ekf->windVelSigma = 0.1f;
		_ekf->dAngBiasSigma = _parameters.gbias_pnoise;
		_ekf->dVelBiasSigma = _parameters.abias_pnoise;
		_ekf->magEarthSigma = _parameters.mage_pnoise;
		_ekf->magBodySigma  = _parameters.magb_pnoise;
		// _ekf->gndHgtSigma  = 0.02f;
		_ekf->vneSigma = _parameters.velne_noise;
		_ekf->vdSigma = _parameters.veld_noise;
		_ekf->posNeSigma = _parameters.posne_noise;
		_ekf->posDSigma = _parameters.posd_noise;
		_ekf->magMeasurementSigma = _parameters.mag_noise;
		_ekf->gyroProcessNoise = _parameters.gyro_pnoise;
        	_ekf->accelProcessNoise = _parameters.acc_pnoise;
		_ekf->airspeedMeasurementSigma = _parameters.eas_noise;
	}

	return OK;
}

void
FixedwingEstimator::vehicle_status_poll()
{
	bool vstatus_updated;

	/* Check HIL state if vehicle status has changed */
	orb_check(_vstatus_sub, &vstatus_updated);

	if (vstatus_updated) {

		orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
	}
}

int
FixedwingEstimator::check_filter_state()
{
	/*
	 *    CHECK IF THE INPUT DATA IS SANE
	 */

	struct ekf_status_report ekf_report;

	int check = _ekf->CheckAndBound(&ekf_report);

	const char* ekfname = "att pos estimator: ";

	switch (check) {
		case 0:
			/* all ok */
			break;
		case 1:
		{
			const char* str = "NaN in states, resetting";
			warnx("%s", str);
			mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}
		case 2:
		{
			const char* str = "stale IMU data, resetting";
			warnx("%s", str);
			mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}
		case 3:
		{
			const char* str = "switching to dynamic state";
			warnx("%s", str);
			mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}
		case 4:
		{
			const char* str = "excessive gyro offsets";
			warnx("%s", str);
			mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}
		case 5:
		{
			const char* str = "GPS velocity divergence";
			warnx("%s", str);
			mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}
		case 6:
		{
			const char* str = "excessive covariances";
			warnx("%s", str);
			mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str);
			break;
		}

		default:
		{
			const char* str = "unknown reset condition";
			warnx("%s", str);
			mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
		}
	}

	struct estimator_status_report rep;
	memset(&rep, 0, sizeof(rep));

	// If error flag is set, we got a filter reset
	if (check && ekf_report.error) {

		// Count the reset condition
		perf_count(_perf_reset);

	} else if (_ekf_logging) {
		_ekf->GetFilterState(&ekf_report);
	}

	if (_ekf_logging || check) {
		rep.timestamp = hrt_absolute_time();

		rep.nan_flags |= (((uint8_t)ekf_report.angNaN)		<< 0);
		rep.nan_flags |= (((uint8_t)ekf_report.summedDelVelNaN)	<< 1);
		rep.nan_flags |= (((uint8_t)ekf_report.KHNaN)		<< 2);
		rep.nan_flags |= (((uint8_t)ekf_report.KHPNaN)		<< 3);
		rep.nan_flags |= (((uint8_t)ekf_report.PNaN)		<< 4);
		rep.nan_flags |= (((uint8_t)ekf_report.covarianceNaN)	<< 5);
		rep.nan_flags |= (((uint8_t)ekf_report.kalmanGainsNaN)	<< 6);
		rep.nan_flags |= (((uint8_t)ekf_report.statesNaN)	<< 7);

		rep.health_flags |= (((uint8_t)ekf_report.velHealth)	<< 0);
		rep.health_flags |= (((uint8_t)ekf_report.posHealth)	<< 1);
		rep.health_flags |= (((uint8_t)ekf_report.hgtHealth)	<< 2);
		rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive)	<< 3);

		rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout)	<< 0);
		rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout)	<< 1);
		rep.timeout_flags |= (((uint8_t)ekf_report.hgtTimeout)	<< 2);
		rep.timeout_flags |= (((uint8_t)ekf_report.imuTimeout)	<< 3);

		if (_debug > 10) {

			if (rep.health_flags < ((1 << 0) | (1 << 1) | (1 << 2) | (1 << 3))) {
				warnx("health: VEL:%s POS:%s HGT:%s OFFS:%s",
					((rep.health_flags & (1 << 0)) ? "OK" : "ERR"),
					((rep.health_flags & (1 << 1)) ? "OK" : "ERR"),
					((rep.health_flags & (1 << 2)) ? "OK" : "ERR"),
					((rep.health_flags & (1 << 3)) ? "OK" : "ERR"));
			}

			if (rep.timeout_flags) {
				warnx("timeout: %s%s%s%s",
					((rep.timeout_flags & (1 << 0)) ? "VEL " : ""),
					((rep.timeout_flags & (1 << 1)) ? "POS " : ""),
					((rep.timeout_flags & (1 << 2)) ? "HGT " : ""),
					((rep.timeout_flags & (1 << 3)) ? "IMU " : ""));
			}
		}

		// Copy all states or at least all that we can fit
		unsigned ekf_n_states = ekf_report.n_states;
		unsigned max_states = (sizeof(rep.states) / sizeof(rep.states[0]));
		rep.n_states = (ekf_n_states < max_states) ? ekf_n_states : max_states;

		for (unsigned i = 0; i < rep.n_states; i++) {
			rep.states[i] = ekf_report.states[i];
		}

		for (unsigned i = 0; i < rep.n_states; i++) {
			rep.states[i] = ekf_report.states[i];
		}

		if (_estimator_status_pub > 0) {
			orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &rep);
		} else {
			_estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &rep);
		}
	}

	return check;
}

void
FixedwingEstimator::task_main_trampoline(int argc, char *argv[])
{
	estimator::g_estimator->task_main();
}

void
FixedwingEstimator::task_main()
{
	_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);

	_ekf = new AttPosEKF();
	float dt = 0.0f; // time lapsed since last covariance prediction
	_filter_start_time = hrt_absolute_time();

	if (!_ekf) {
		errx(1, "OUT OF MEM!");
	}

	/*
	 * do subscriptions
	 */
	_baro_sub = orb_subscribe(ORB_ID(sensor_baro));
	_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
	_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
	_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
	_params_sub = orb_subscribe(ORB_ID(parameter_update));
	_home_sub = orb_subscribe(ORB_ID(home_position));

	/* rate limit vehicle status updates to 5Hz */
	orb_set_interval(_vstatus_sub, 200);

#ifndef SENSOR_COMBINED_SUB

	_gyro_sub = orb_subscribe(ORB_ID(sensor_gyro));
	_accel_sub = orb_subscribe(ORB_ID(sensor_accel));
	_mag_sub = orb_subscribe(ORB_ID(sensor_mag));

	/* rate limit gyro updates to 50 Hz */
	/* XXX remove this!, BUT increase the data buffer size! */
	orb_set_interval(_gyro_sub, 4);
#else
	_sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
	/* XXX remove this!, BUT increase the data buffer size! */
	orb_set_interval(_sensor_combined_sub, 9);
#endif

	/* sets also parameters in the EKF object */
	parameters_update();

	Vector3f lastAngRate = {0.0f, 0.0f, 0.0f};
	Vector3f lastAccel = {0.0f, 0.0f, 0.0f};

	/* wakeup source(s) */
	struct pollfd fds[2];

	/* Setup of loop */
	fds[0].fd = _params_sub;
	fds[0].events = POLLIN;
#ifndef SENSOR_COMBINED_SUB
	fds[1].fd = _gyro_sub;
	fds[1].events = POLLIN;
#else
	fds[1].fd = _sensor_combined_sub;
	fds[1].events = POLLIN;
#endif

	bool newDataGps = false;
	bool newHgtData = false;
	bool newAdsData = false;
	bool newDataMag = false;

	float posNED[3] = {0.0f, 0.0f, 0.0f}; // North, East Down position (m)

	uint64_t last_gps = 0;
	_gps.vel_n_m_s = 0.0f;
	_gps.vel_e_m_s = 0.0f;
	_gps.vel_d_m_s = 0.0f;

	while (!_task_should_exit) {

		/* wait for up to 500ms for data */
		int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);

		/* timed out - periodic check for _task_should_exit, etc. */
		if (pret == 0)
			continue;

		/* this is undesirable but not much we can do - might want to flag unhappy status */
		if (pret < 0) {
			warn("POLL ERR %d, %d", pret, errno);
			continue;
		}

		perf_begin(_loop_perf);

		/* only update parameters if they changed */
		if (fds[0].revents & POLLIN) {
			/* read from param to clear updated flag */
			struct parameter_update_s update;
			orb_copy(ORB_ID(parameter_update), _params_sub, &update);

			/* update parameters from storage */
			parameters_update();
		}

		/* only run estimator if gyro updated */
		if (fds[1].revents & POLLIN) {

			/* check vehicle status for changes to publication state */
			bool prev_hil = (_vstatus.hil_state == HIL_STATE_ON);
			vehicle_status_poll();

			bool accel_updated;
			bool mag_updated;

			perf_count(_perf_gyro);

			/* Reset baro reference if switching to HIL, reset sensor states */
			if (!prev_hil && (_vstatus.hil_state == HIL_STATE_ON)) {
				/* system is in HIL now, wait for measurements to come in one last round */
				usleep(60000);

#ifndef SENSOR_COMBINED_SUB
				orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro);
				orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
				orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag);
#else
				/* now read all sensor publications to ensure all real sensor data is purged */
				orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
#endif

				/* set sensors to de-initialized state */
				_gyro_valid = false;
				_accel_valid = false;
				_mag_valid = false;

				_baro_init = false;
				_gps_initialized = false;
				_last_sensor_timestamp = hrt_absolute_time();
				_last_run = _last_sensor_timestamp;

				_ekf->ZeroVariables();
				_ekf->dtIMU = 0.01f;
				_filter_start_time = _last_sensor_timestamp;

				/* now skip this loop and get data on the next one, which will also re-init the filter */
				continue;
			}

			/**
			 *    PART ONE: COLLECT ALL DATA
			 **/

			/* load local copies */
#ifndef SENSOR_COMBINED_SUB
			orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro);


			orb_check(_accel_sub, &accel_updated);

			if (accel_updated) {
				orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
			}

			_last_sensor_timestamp = _gyro.timestamp;
			IMUmsec = _gyro.timestamp / 1e3f;

			float deltaT = (_gyro.timestamp - _last_run) / 1e6f;
			_last_run = _gyro.timestamp;

			/* guard against too large deltaT's */
			if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
				deltaT = 0.01f;
			}


			// Always store data, independent of init status
			/* fill in last data set */
			_ekf->dtIMU = deltaT;

			if (isfinite(_gyro.x) &&
				isfinite(_gyro.y) &&
				isfinite(_gyro.z)) {
				_ekf->angRate.x = _gyro.x;
				_ekf->angRate.y = _gyro.y;
				_ekf->angRate.z = _gyro.z;

				if (!_gyro_valid) {
					lastAngRate = _ekf->angRate;
				}

				_gyro_valid = true;
			}

			if (accel_updated) {
				_ekf->accel.x = _accel.x;
				_ekf->accel.y = _accel.y;
				_ekf->accel.z = _accel.z;

				if (!_accel_valid) {
					lastAccel = _ekf->accel;
				}

				_accel_valid = true;
			}

			_ekf->dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU;
			_ekf->lastAngRate = angRate;
			_ekf->dVelIMU = 0.5f * (accel + lastAccel) * dtIMU;
			_ekf->lastAccel = accel;


#else
			orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);

			static hrt_abstime last_accel = 0;
			static hrt_abstime last_mag = 0;

			if (last_accel != _sensor_combined.accelerometer_timestamp) {
				accel_updated = true;
			} else {
				accel_updated = false;
			}

			last_accel = _sensor_combined.accelerometer_timestamp;


			// Copy gyro and accel
			_last_sensor_timestamp = _sensor_combined.timestamp;
			IMUmsec = _sensor_combined.timestamp / 1e3f;

			float deltaT = (_sensor_combined.timestamp - _last_run) / 1e6f;

			/* guard against too large deltaT's */
			if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
				deltaT = 0.01f;
			}

			_last_run = _sensor_combined.timestamp;

			// Always store data, independent of init status
			/* fill in last data set */
			_ekf->dtIMU = deltaT;

			if (isfinite(_sensor_combined.gyro_rad_s[0]) &&
				isfinite(_sensor_combined.gyro_rad_s[1]) &&
				isfinite(_sensor_combined.gyro_rad_s[2])) {
				_ekf->angRate.x = _sensor_combined.gyro_rad_s[0];
				_ekf->angRate.y = _sensor_combined.gyro_rad_s[1];
				_ekf->angRate.z = _sensor_combined.gyro_rad_s[2];

				if (!_gyro_valid) {
					lastAngRate = _ekf->angRate;
				}

				_gyro_valid = true;
				perf_count(_perf_gyro);
			}

			if (accel_updated) {
				_ekf->accel.x = _sensor_combined.accelerometer_m_s2[0];
				_ekf->accel.y = _sensor_combined.accelerometer_m_s2[1];
				_ekf->accel.z = _sensor_combined.accelerometer_m_s2[2];

				if (!_accel_valid) {
					lastAccel = _ekf->accel;
				}

				_accel_valid = true;
			}

			_ekf->dAngIMU = 0.5f * (_ekf->angRate + lastAngRate) * _ekf->dtIMU;
			lastAngRate = _ekf->angRate;
			_ekf->dVelIMU = 0.5f * (_ekf->accel + lastAccel) * _ekf->dtIMU;
			lastAccel = _ekf->accel;

			if (last_mag != _sensor_combined.magnetometer_timestamp) {
				mag_updated = true;
				newDataMag = true;

			} else {
				newDataMag = false;
			}

			last_mag = _sensor_combined.magnetometer_timestamp;

#endif

			//warnx("dang: %8.4f %8.4f dvel: %8.4f %8.4f", _ekf->dAngIMU.x, _ekf->dAngIMU.z, _ekf->dVelIMU.x, _ekf->dVelIMU.z);

			bool airspeed_updated;
			orb_check(_airspeed_sub, &airspeed_updated);

			if (airspeed_updated) {
				orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
				perf_count(_perf_airspeed);

				_ekf->VtasMeas = _airspeed.true_airspeed_m_s;
				newAdsData = true;

			} else {
				newAdsData = false;
			}

			bool gps_updated;
			orb_check(_gps_sub, &gps_updated);

			if (gps_updated) {

				last_gps = _gps.timestamp_position;

				orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps);
				perf_count(_perf_gps);

				if (_gps.fix_type < 3) {
					newDataGps = false;

				} else {

					/* store time of valid GPS measurement */
					_gps_start_time = hrt_absolute_time();

					/* check if we had a GPS outage for a long time */
					if (hrt_elapsed_time(&last_gps) > 5 * 1000 * 1000) {
						_ekf->ResetPosition();
						_ekf->ResetVelocity();
						_ekf->ResetStoredStates();
					}

					/* fuse GPS updates */

					//_gps.timestamp / 1e3;
					_ekf->GPSstatus = _gps.fix_type;
					_ekf->velNED[0] = _gps.vel_n_m_s;
					_ekf->velNED[1] = _gps.vel_e_m_s;
					_ekf->velNED[2] = _gps.vel_d_m_s;

					// warnx("GPS updated: status: %d, vel: %8.4f %8.4f %8.4f", (int)GPSstatus, velNED[0], velNED[1], velNED[2]);

					_ekf->gpsLat = math::radians(_gps.lat / (double)1e7);
					_ekf->gpsLon = math::radians(_gps.lon / (double)1e7) - M_PI;
					_ekf->gpsHgt = _gps.alt / 1e3f;

					// if (_gps.s_variance_m_s > 0.25f && _gps.s_variance_m_s < 100.0f * 100.0f) {
					// 	_ekf->vneSigma = sqrtf(_gps.s_variance_m_s);
					// } else {
					// 	_ekf->vneSigma = _parameters.velne_noise;
					// }

					// if (_gps.p_variance_m > 0.25f && _gps.p_variance_m < 100.0f * 100.0f) {
					// 	_ekf->posNeSigma = sqrtf(_gps.p_variance_m);
					// } else {
					// 	_ekf->posNeSigma = _parameters.posne_noise;
					// }

					// warnx("vel: %8.4f pos: %8.4f", _gps.s_variance_m_s, _gps.p_variance_m);

					newDataGps = true;

				}

			}

			bool baro_updated;
			orb_check(_baro_sub, &baro_updated);

			if (baro_updated) {
				orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);

				_ekf->baroHgt = _baro.altitude;

				if (!_baro_init) {
					_baro_ref = _baro.altitude;
					_baro_init = true;
					warnx("ALT REF INIT");
				}

				perf_count(_perf_baro);

				newHgtData = true;
			} else {
				newHgtData = false;
			}

#ifndef SENSOR_COMBINED_SUB
			orb_check(_mag_sub, &mag_updated);
#endif

			if (mag_updated) {

				_mag_valid = true;

				perf_count(_perf_mag);

#ifndef SENSOR_COMBINED_SUB
				orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag);

				// XXX we compensate the offsets upfront - should be close to zero.
				// 0.001f
				_ekf->magData.x = _mag.x;
				_ekf->magBias.x = 0.000001f; // _mag_offsets.x_offset

				_ekf->magData.y = _mag.y;
				_ekf->magBias.y = 0.000001f; // _mag_offsets.y_offset

				_ekf->magData.z = _mag.z;
				_ekf->magBias.z = 0.000001f; // _mag_offsets.y_offset

#else

				// XXX we compensate the offsets upfront - should be close to zero.
				// 0.001f
				_ekf->magData.x = _sensor_combined.magnetometer_ga[0];
				_ekf->magBias.x = 0.000001f; // _mag_offsets.x_offset

				_ekf->magData.y = _sensor_combined.magnetometer_ga[1];
				_ekf->magBias.y = 0.000001f; // _mag_offsets.y_offset

				_ekf->magData.z = _sensor_combined.magnetometer_ga[2];
				_ekf->magBias.z = 0.000001f; // _mag_offsets.y_offset

#endif

				newDataMag = true;

			} else {
				newDataMag = false;
			}

			/*
			 *    CHECK IF ITS THE RIGHT TIME TO RUN THINGS ALREADY
			 */
			if (hrt_elapsed_time(&_filter_start_time) < FILTER_INIT_DELAY) {
				continue;
			}

			/**
			 *    PART TWO: EXECUTE THE FILTER
			 *
			 *    We run the filter only once all data has been fetched
			 **/

			if (_baro_init && _gyro_valid && _accel_valid && _mag_valid) {

				float initVelNED[3];

				/* Initialize the filter first */
				if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) {

					// GPS is in scaled integers, convert
					double lat = _gps.lat / 1.0e7;
					double lon = _gps.lon / 1.0e7;
					float gps_alt = _gps.alt / 1e3f;

					initVelNED[0] = _gps.vel_n_m_s;
					initVelNED[1] = _gps.vel_e_m_s;
					initVelNED[2] = _gps.vel_d_m_s;

					// Set up height correctly
					orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
					_baro_ref_offset = _ekf->states[9]; // this should become zero in the local frame
					_baro_gps_offset = _baro.altitude - gps_alt;
					_ekf->baroHgt = _baro.altitude;
					_ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref));

					// Set up position variables correctly
					_ekf->GPSstatus = _gps.fix_type;

					_ekf->gpsLat = math::radians(lat);
					_ekf->gpsLon = math::radians(lon) - M_PI;
					_ekf->gpsHgt = gps_alt;

					// Look up mag declination based on current position
					float declination = math::radians(get_mag_declination(lat, lon));

					_ekf->InitialiseFilter(initVelNED, math::radians(lat), math::radians(lon) - M_PI, gps_alt, declination);

					// Initialize projection
					_local_pos.ref_lat = lat;
					_local_pos.ref_lon = lon;
					_local_pos.ref_alt = gps_alt;
					_local_pos.ref_timestamp = _gps.timestamp_position;

					map_projection_init(&_pos_ref, lat, lon);
					mavlink_log_info(_mavlink_fd, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt);

					#if 0
					warnx("HOME/REF: LA %8.4f,LO %8.4f,ALT %8.2f V: %8.4f %8.4f %8.4f", lat, lon, (double)gps_alt,
						(double)_ekf->velNED[0], (double)_ekf->velNED[1], (double)_ekf->velNED[2]);
					warnx("BARO: %8.4f m / ref: %8.4f m / gps offs: %8.4f m", (double)_ekf->baroHgt, (double)_baro_ref, (double)_baro_ref_offset);
					warnx("GPS: eph: %8.4f, epv: %8.4f, declination: %8.4f", (double)_gps.eph, (double)_gps.epv, (double)math::degrees(declination));
					#endif

					_gps_initialized = true;

				} else if (!_ekf->statesInitialised) {

					initVelNED[0] = 0.0f;
					initVelNED[1] = 0.0f;
					initVelNED[2] = 0.0f;
					_ekf->posNE[0] = posNED[0];
					_ekf->posNE[1] = posNED[1];

					_local_pos.ref_alt = _baro_ref;
					_baro_ref_offset = 0.0f;
					_baro_gps_offset = 0.0f;

					_ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f);
				} else if (_ekf->statesInitialised) {

					// We're apparently initialized in this case now

					int check = check_filter_state();

					if (check) {
						// Let the system re-initialize itself
						continue;
					}


					// Run the strapdown INS equations every IMU update
					_ekf->UpdateStrapdownEquationsNED();
	#if 0
					// debug code - could be tunred into a filter mnitoring/watchdog function
					float tempQuat[4];

					for (uint8_t j = 0; j <= 3; j++) tempQuat[j] = states[j];

					quat2eul(eulerEst, tempQuat);

					for (uint8_t j = 0; j <= 2; j++) eulerDif[j] = eulerEst[j] - ahrsEul[j];

					if (eulerDif[2] > pi) eulerDif[2] -= 2 * pi;

					if (eulerDif[2] < -pi) eulerDif[2] += 2 * pi;

	#endif
					// store the predicted states for subsequent use by measurement fusion
					_ekf->StoreStates(IMUmsec);
					// Check if on ground - status is used by covariance prediction
					_ekf->OnGroundCheck();
					// sum delta angles and time used by covariance prediction
					_ekf->summedDelAng = _ekf->summedDelAng + _ekf->correctedDelAng;
					_ekf->summedDelVel = _ekf->summedDelVel + _ekf->dVelIMU;
					dt += _ekf->dtIMU;

					// perform a covariance prediction if the total delta angle has exceeded the limit
					// or the time limit will be exceeded at the next IMU update
					if ((dt >= (_ekf->covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > _ekf->covDelAngMax)) {
						_ekf->CovariancePrediction(dt);
						_ekf->summedDelAng.zero();
						_ekf->summedDelVel.zero();
						dt = 0.0f;
					}

					// Fuse GPS Measurements
					if (newDataGps && _gps_initialized) {
						// Convert GPS measurements to Pos NE, hgt and Vel NED

						float gps_dt = (_gps.timestamp_position - last_gps) / 1e6f;

						// Calculate acceleration predicted by GPS velocity change
						if (((fabsf(_ekf->velNED[0] - _gps.vel_n_m_s) > FLT_EPSILON) ||
							(fabsf(_ekf->velNED[1] - _gps.vel_e_m_s) > FLT_EPSILON) ||
							(fabsf(_ekf->velNED[2] - _gps.vel_d_m_s) > FLT_EPSILON)) && (gps_dt > 0.00001f)) {

							_ekf->accelGPSNED[0] = (_ekf->velNED[0] - _gps.vel_n_m_s) / gps_dt;
							_ekf->accelGPSNED[1] = (_ekf->velNED[1] - _gps.vel_e_m_s) / gps_dt;
							_ekf->accelGPSNED[2] = (_ekf->velNED[2] - _gps.vel_d_m_s) / gps_dt;
						}

						_ekf->velNED[0] = _gps.vel_n_m_s;
						_ekf->velNED[1] = _gps.vel_e_m_s;
						_ekf->velNED[2] = _gps.vel_d_m_s;
						_ekf->calcposNED(posNED, _ekf->gpsLat, _ekf->gpsLon, _ekf->gpsHgt, _ekf->latRef, _ekf->lonRef, _ekf->hgtRef);

						_ekf->posNE[0] = posNED[0];
						_ekf->posNE[1] = posNED[1];
						// set fusion flags
						_ekf->fuseVelData = true;
						_ekf->fusePosData = true;
						// recall states stored at time of measurement after adjusting for delays
						_ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
						_ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
						// run the fusion step
						_ekf->FuseVelposNED();

					} else if (_ekf->statesInitialised) {
						// Convert GPS measurements to Pos NE, hgt and Vel NED
						_ekf->velNED[0] = 0.0f;
						_ekf->velNED[1] = 0.0f;
						_ekf->velNED[2] = 0.0f;

						_ekf->posNE[0] = 0.0f;
						_ekf->posNE[1] = 0.0f;
						// set fusion flags
						_ekf->fuseVelData = true;
						_ekf->fusePosData = true;
						// recall states stored at time of measurement after adjusting for delays
						_ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
						_ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
						// run the fusion step
						_ekf->FuseVelposNED();

					} else {
						_ekf->fuseVelData = false;
						_ekf->fusePosData = false;
					}

					if (newHgtData && _ekf->statesInitialised) {
						// Could use a blend of GPS and baro alt data if desired
						_ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref);
						_ekf->fuseHgtData = true;
						// recall states stored at time of measurement after adjusting for delays
						_ekf->RecallStates(_ekf->statesAtHgtTime, (IMUmsec - _parameters.height_delay_ms));
						// run the fusion step
						_ekf->FuseVelposNED();

					} else {
						_ekf->fuseHgtData = false;
					}

					// Fuse Magnetometer Measurements
					if (newDataMag && _ekf->statesInitialised) {
						_ekf->fuseMagData = true;
						_ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data

						_ekf->magstate.obsIndex = 0;
						_ekf->FuseMagnetometer();
						_ekf->FuseMagnetometer();
						_ekf->FuseMagnetometer();

					} else {
						_ekf->fuseMagData = false;
					}

					// Fuse Airspeed Measurements
					if (newAdsData && _ekf->statesInitialised && _ekf->VtasMeas > 8.0f) {
						_ekf->fuseVtasData = true;
						_ekf->RecallStates(_ekf->statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data
						_ekf->FuseAirspeed();

					} else {
						_ekf->fuseVtasData = false;
					}


					// Output results
					math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->states[3]);
					math::Matrix<3, 3> R = q.to_dcm();
					math::Vector<3> euler = R.to_euler();

					for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
							_att.R[i][j] = R(i, j);

					_att.timestamp = _last_sensor_timestamp;
					_att.q[0] = _ekf->states[0];
					_att.q[1] = _ekf->states[1];
					_att.q[2] = _ekf->states[2];
					_att.q[3] = _ekf->states[3];
					_att.q_valid = true;
					_att.R_valid = true;

					_att.timestamp = _last_sensor_timestamp;
					_att.roll = euler(0);
					_att.pitch = euler(1);
					_att.yaw = euler(2);

					_att.rollspeed = _ekf->angRate.x - _ekf->states[10];
					_att.pitchspeed = _ekf->angRate.y - _ekf->states[11];
					_att.yawspeed = _ekf->angRate.z - _ekf->states[12];
					// gyro offsets
					_att.rate_offsets[0] = _ekf->states[10];
					_att.rate_offsets[1] = _ekf->states[11];
					_att.rate_offsets[2] = _ekf->states[12];

					/* lazily publish the attitude only once available */
					if (_att_pub > 0) {
						/* publish the attitude setpoint */
						orb_publish(ORB_ID(vehicle_attitude), _att_pub, &_att);

					} else {
						/* advertise and publish */
						_att_pub = orb_advertise(ORB_ID(vehicle_attitude), &_att);
					}

					if (_gps_initialized) {
						_local_pos.timestamp = _last_sensor_timestamp;
						_local_pos.x = _ekf->states[7];
						_local_pos.y = _ekf->states[8];
						// XXX need to announce change of Z reference somehow elegantly
						_local_pos.z = _ekf->states[9] - _baro_ref_offset;

						_local_pos.vx = _ekf->states[4];
						_local_pos.vy = _ekf->states[5];
						_local_pos.vz = _ekf->states[6];

						_local_pos.xy_valid = _gps_initialized;
						_local_pos.z_valid = true;
						_local_pos.v_xy_valid = _gps_initialized;
						_local_pos.v_z_valid = true;
						_local_pos.xy_global = true;

						_velocity_xy_filtered = 0.95f*_velocity_xy_filtered + 0.05f*sqrtf(_local_pos.vx*_local_pos.vx + _local_pos.vy*_local_pos.vy);
						_velocity_z_filtered = 0.95f*_velocity_z_filtered + 0.05f*fabsf(_local_pos.vz);
						_airspeed_filtered = 0.95f*_airspeed_filtered + + 0.05f*_airspeed.true_airspeed_m_s;


						/* crude land detector for fixedwing only,
						* TODO: adapt so that it works for both, maybe move to another location
						*/
						if (_velocity_xy_filtered < 5
							&& _velocity_z_filtered < 10
							&& _airspeed_filtered < 10) {
							_local_pos.landed = true;
						} else {
							_local_pos.landed = false;
						}

						_local_pos.z_global = false;
						_local_pos.yaw = _att.yaw;

						/* lazily publish the local position only once available */
						if (_local_pos_pub > 0) {
							/* publish the attitude setpoint */
							orb_publish(ORB_ID(vehicle_local_position), _local_pos_pub, &_local_pos);

						} else {
							/* advertise and publish */
							_local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &_local_pos);
						}

						_global_pos.timestamp = _local_pos.timestamp;

						if (_local_pos.xy_global) {
							double est_lat, est_lon;
							map_projection_reproject(&_pos_ref, _local_pos.x, _local_pos.y, &est_lat, &est_lon);
							_global_pos.lat = est_lat;
							_global_pos.lon = est_lon;
							_global_pos.time_gps_usec = _gps.time_gps_usec;
							_global_pos.eph = _gps.eph;
							_global_pos.epv = _gps.epv;
						}

						if (_local_pos.v_xy_valid) {
							_global_pos.vel_n = _local_pos.vx;
							_global_pos.vel_e = _local_pos.vy;
						} else {
							_global_pos.vel_n = 0.0f;
							_global_pos.vel_e = 0.0f;
						}

						/* local pos alt is negative, change sign and add alt offsets */
						_global_pos.alt = _baro_ref + (-_local_pos.z) - _baro_gps_offset;

						if (_local_pos.v_z_valid) {
							_global_pos.vel_d = _local_pos.vz;
						}


						_global_pos.yaw = _local_pos.yaw;

						_global_pos.eph = _gps.eph;
						_global_pos.epv = _gps.epv;

						_global_pos.timestamp = _local_pos.timestamp;

						/* lazily publish the global position only once available */
						if (_global_pos_pub > 0) {
							/* publish the global position */
							orb_publish(ORB_ID(vehicle_global_position), _global_pos_pub, &_global_pos);

						} else {
							/* advertise and publish */
							_global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos);
						}

						if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
							_wind.timestamp = _global_pos.timestamp;
							_wind.windspeed_north = _ekf->states[14];
							_wind.windspeed_east = _ekf->states[15];
							_wind.covariance_north = 0.0f; // XXX get form filter
							_wind.covariance_east = 0.0f;

							/* lazily publish the wind estimate only once available */
							if (_wind_pub > 0) {
								/* publish the wind estimate */
								orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);

							} else {
								/* advertise and publish */
								_wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
							}

						}

					}

				}

				if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
					_wind.timestamp = _global_pos.timestamp;
					_wind.windspeed_north = _ekf->states[14];
					_wind.windspeed_east = _ekf->states[15];
					_wind.covariance_north = _ekf->P[14][14];
					_wind.covariance_east = _ekf->P[15][15];

					/* lazily publish the wind estimate only once available */
					if (_wind_pub > 0) {
						/* publish the wind estimate */
						orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);

					} else {
						/* advertise and publish */
						_wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
					}
				}
			}

		}

		perf_end(_loop_perf);
	}

	warnx("exiting.\n");

	_estimator_task = -1;
	_exit(0);
}

int
FixedwingEstimator::start()
{
	ASSERT(_estimator_task == -1);

	/* start the task */
	_estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
					 SCHED_DEFAULT,
					 SCHED_PRIORITY_MAX - 40,
					 5000,
					 (main_t)&FixedwingEstimator::task_main_trampoline,
					 nullptr);

	if (_estimator_task < 0) {
		warn("task start failed");
		return -errno;
	}

	return OK;
}

void
FixedwingEstimator::print_status()
{
	math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->states[3]);
	math::Matrix<3, 3> R = q.to_dcm();
	math::Vector<3> euler = R.to_euler();

	printf("attitude: roll: %8.4f, pitch %8.4f, yaw: %8.4f degrees\n",
	       (double)math::degrees(euler(0)), (double)math::degrees(euler(1)), (double)math::degrees(euler(2)));

	// State vector:
	// 0-3: quaternions (q0, q1, q2, q3)
	// 4-6: Velocity - m/sec (North, East, Down)
	// 7-9: Position - m (North, East, Down)
	// 10-12: Delta Angle bias - rad (X,Y,Z)
	// 13:    Accelerometer offset
	// 14-15: Wind Vector  - m/sec (North,East)
	// 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
	// 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)

	printf("dtIMU: %8.6f IMUmsec: %d\n", (double)_ekf->dtIMU, (int)IMUmsec);
	printf("baro alt: %8.4f GPS alt: %8.4f\n", (double)_baro.altitude, (double)(_gps.alt / 1e3f));
	printf("ref alt: %8.4f baro ref offset: %8.4f baro GPS offset: %8.4f\n", (double)_baro_ref, (double)_baro_ref_offset, (double)_baro_gps_offset);
	printf("dvel: %8.6f %8.6f %8.6f accel: %8.6f %8.6f %8.6f\n", (double)_ekf->dVelIMU.x, (double)_ekf->dVelIMU.y, (double)_ekf->dVelIMU.z, (double)_ekf->accel.x, (double)_ekf->accel.y, (double)_ekf->accel.z);
	printf("dang: %8.4f %8.4f %8.4f dang corr: %8.4f %8.4f %8.4f\n" , (double)_ekf->dAngIMU.x, (double)_ekf->dAngIMU.y, (double)_ekf->dAngIMU.z, (double)_ekf->correctedDelAng.x, (double)_ekf->correctedDelAng.y, (double)_ekf->correctedDelAng.z);
	printf("states (quat)        [0-3]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[0], (double)_ekf->states[1], (double)_ekf->states[2], (double)_ekf->states[3]);
	printf("states (vel m/s)     [4-6]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[4], (double)_ekf->states[5], (double)_ekf->states[6]);
	printf("states (pos m)      [7-9]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[7], (double)_ekf->states[8], (double)_ekf->states[9]);
	printf("states (delta ang) [10-12]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[10], (double)_ekf->states[11], (double)_ekf->states[12]);

	if (n_states == 23) {
		printf("states (accel offs)   [13]: %8.4f\n", (double)_ekf->states[13]);
		printf("states (wind)      [14-15]: %8.4f, %8.4f\n", (double)_ekf->states[14], (double)_ekf->states[15]);
		printf("states (earth mag) [16-18]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[16], (double)_ekf->states[17], (double)_ekf->states[18]);
		printf("states (body mag)  [19-21]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[19], (double)_ekf->states[20], (double)_ekf->states[21]);
		printf("states (terrain)      [22]: %8.4f\n", (double)_ekf->states[22]);

	} else {
		printf("states (wind)      [13-14]: %8.4f, %8.4f\n", (double)_ekf->states[13], (double)_ekf->states[14]);
		printf("states (earth mag) [15-17]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[15], (double)_ekf->states[16], (double)_ekf->states[17]);
		printf("states (body mag)  [18-20]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[18], (double)_ekf->states[19], (double)_ekf->states[20]);
	}
	printf("states: %s %s %s %s %s %s %s %s %s %s\n",
		       (_ekf->statesInitialised) ? "INITIALIZED" : "NON_INIT",
		       (_ekf->onGround) ? "ON_GROUND" : "AIRBORNE",
		       (_ekf->fuseVelData) ? "FUSE_VEL" : "INH_VEL",
		       (_ekf->fusePosData) ? "FUSE_POS" : "INH_POS",
		       (_ekf->fuseHgtData) ? "FUSE_HGT" : "INH_HGT",
		       (_ekf->fuseMagData) ? "FUSE_MAG" : "INH_MAG",
		       (_ekf->fuseVtasData) ? "FUSE_VTAS" : "INH_VTAS",
		       (_ekf->useAirspeed) ? "USE_AIRSPD" : "IGN_AIRSPD",
		       (_ekf->useCompass) ? "USE_COMPASS" : "IGN_COMPASS",
		       (_ekf->staticMode) ? "STATIC_MODE" : "DYNAMIC_MODE");
}

int FixedwingEstimator::trip_nan() {

	int ret = 0;

	// If system is not armed, inject a NaN value into the filter
	int armed_sub = orb_subscribe(ORB_ID(actuator_armed));

	struct actuator_armed_s armed;
	orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);

	if (armed.armed) {
		warnx("ACTUATORS ARMED! NOT TRIPPING SYSTEM");
		ret = 1;
	} else {

		float nan_val = 0.0f / 0.0f;

		warnx("system not armed, tripping state vector with NaN values");
		_ekf->states[5] = nan_val;
		usleep(100000);

		warnx("tripping covariance #1 with NaN values");
		_ekf->KH[2][2] = nan_val; //  intermediate result used for covariance updates
		usleep(100000);

		warnx("tripping covariance #2 with NaN values");
		_ekf->KHP[5][5] = nan_val; // intermediate result used for covariance updates
		usleep(100000);

		warnx("tripping covariance #3 with NaN values");
		_ekf->P[3][3] = nan_val; // covariance matrix
		usleep(100000);

		warnx("tripping Kalman gains with NaN values");
		_ekf->Kfusion[0] = nan_val; // Kalman gains
		usleep(100000);

		warnx("tripping stored states[0] with NaN values");
		_ekf->storedStates[0][0] = nan_val;
		usleep(100000);

		warnx("\nDONE - FILTER STATE:");
		print_status();
	}

	close(armed_sub);
	return ret;
}

int ekf_att_pos_estimator_main(int argc, char *argv[])
{
	if (argc < 1)
		errx(1, "usage: ekf_att_pos_estimator {start|stop|status|logging}");

	if (!strcmp(argv[1], "start")) {

		if (estimator::g_estimator != nullptr)
			errx(1, "already running");

		estimator::g_estimator = new FixedwingEstimator;

		if (estimator::g_estimator == nullptr)
			errx(1, "alloc failed");

		if (OK != estimator::g_estimator->start()) {
			delete estimator::g_estimator;
			estimator::g_estimator = nullptr;
			err(1, "start failed");
		}

		exit(0);
	}

	if (!strcmp(argv[1], "stop")) {
		if (estimator::g_estimator == nullptr)
			errx(1, "not running");

		delete estimator::g_estimator;
		estimator::g_estimator = nullptr;
		exit(0);
	}

	if (!strcmp(argv[1], "status")) {
		if (estimator::g_estimator) {
			warnx("running");

			estimator::g_estimator->print_status();

			exit(0);

		} else {
			errx(1, "not running");
		}
	}

	if (!strcmp(argv[1], "trip")) {
		if (estimator::g_estimator) {
			int ret = estimator::g_estimator->trip_nan();

			exit(ret);

		} else {
			errx(1, "not running");
		}
	}

	if (!strcmp(argv[1], "logging")) {
		if (estimator::g_estimator) {
			int ret = estimator::g_estimator->enable_logging(true);

			exit(ret);

		} else {
			errx(1, "not running");
		}
	}

	if (!strcmp(argv[1], "debug")) {
		if (estimator::g_estimator) {
			int debug = strtoul(argv[2], NULL, 10);
			int ret = estimator::g_estimator->set_debuglevel(debug);

			exit(ret);

		} else {
			errx(1, "not running");
		}
	}

	warnx("unrecognized command");
	return 1;
}