@@ -1810,6 +1810,65 @@ public float ter_alt
1810
1810
[ DisplayText ( "EFI Fuel Consumed (g)" ) ]
1811
1811
public float efi_fuelconsumed { get ; private set ; }
1812
1812
1813
+ [ GroupText ( "Transponder Status" ) ]
1814
+ [ DisplayText ( "Transponder 1090ES Tx Enabled" ) ]
1815
+ public bool xpdr_es1090_tx_enabled { get ; private set ; }
1816
+ [ GroupText ( "Transponder Status" ) ]
1817
+ [ DisplayText ( "Transponder Mode S Reply Enabled" ) ]
1818
+ public bool xpdr_mode_S_enabled { get ; private set ; }
1819
+ [ GroupText ( "Transponder Status" ) ]
1820
+ [ DisplayText ( "Transponder Mode C Reply Enabled" ) ]
1821
+ public bool xpdr_mode_C_enabled { get ; private set ; }
1822
+ [ GroupText ( "Transponder Status" ) ]
1823
+ [ DisplayText ( "Transponder Mode A Reply Enabled" ) ]
1824
+ public bool xpdr_mode_A_enabled { get ; private set ; }
1825
+ [ GroupText ( "Transponder Status" ) ]
1826
+ [ DisplayText ( "Ident Active" ) ]
1827
+ public bool xpdr_ident_active { get ; private set ; }
1828
+ [ GroupText ( "Transponder Status" ) ]
1829
+ [ DisplayText ( "X-bit Status" ) ]
1830
+ public bool xpdr_x_bit_status { get ; private set ; }
1831
+ [ GroupText ( "Transponder Status" ) ]
1832
+ [ DisplayText ( "Interrogated since last" ) ]
1833
+ public bool xpdr_interrogated_since_last { get ; private set ; }
1834
+ [ GroupText ( "Transponder Status" ) ]
1835
+ [ DisplayText ( "Airborne" ) ]
1836
+ public bool xpdr_airborne_status { get ; private set ; }
1837
+ [ GroupText ( "Transponder Status" ) ]
1838
+ [ DisplayText ( "Transponder Mode A squawk code" ) ]
1839
+ public ushort xpdr_mode_A_squawk_code { get ; private set ; }
1840
+ [ GroupText ( "Transponder Status" ) ]
1841
+ [ DisplayText ( "NIC" ) ]
1842
+ public byte xpdr_nic { get ; private set ; }
1843
+ [ GroupText ( "Transponder Status" ) ]
1844
+ [ DisplayText ( "NACp" ) ]
1845
+ public byte xpdr_nacp { get ; private set ; }
1846
+ [ GroupText ( "Transponder Status" ) ]
1847
+ [ DisplayText ( "Board Temperature in C" ) ]
1848
+ public byte xpdr_board_temperature { get ; private set ; }
1849
+ [ GroupText ( "Transponder Status" ) ]
1850
+ [ DisplayText ( "Maintainence Required" ) ]
1851
+ public bool xpdr_maint_req { get ; private set ; }
1852
+ [ GroupText ( "Transponder Status" ) ]
1853
+ [ DisplayText ( "ADSB Tx System Failure" ) ]
1854
+ public bool xpdr_adsb_tx_sys_fail { get ; private set ; }
1855
+ [ GroupText ( "Transponder Status" ) ]
1856
+ [ DisplayText ( "GPS Unavailable" ) ]
1857
+ public bool xpdr_gps_unavail { get ; private set ; }
1858
+ [ GroupText ( "Transponder Status" ) ]
1859
+ [ DisplayText ( "GPS No Fix" ) ]
1860
+ public bool xpdr_gps_no_fix { get ; private set ; }
1861
+ [ GroupText ( "Transponder Status" ) ]
1862
+ [ DisplayText ( "Ping200X No Status Message Recieved" ) ]
1863
+ public bool xpdr_status_unavail { get ; private set ; }
1864
+ [ GroupText ( "Transponder Status" ) ]
1865
+ [ DisplayText ( "Status Update Pending" ) ]
1866
+ public bool xpdr_status_pending { get ; set ; }
1867
+ [ GroupText ( "Transponder Status" ) ]
1868
+ [ DisplayText ( "Callsign/Flight ID" ) ]
1869
+ public byte [ ] xpdr_flight_id { get ; set ; }
1870
+
1871
+
1813
1872
public object Clone ( )
1814
1873
{
1815
1874
return MemberwiseClone ( ) ;
@@ -3334,6 +3393,35 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
3334
3393
3335
3394
}
3336
3395
break ;
3396
+ case ( uint ) MAVLink . MAVLINK_MSG_ID . UAVIONIX_ADSB_OUT_STATUS :
3397
+ {
3398
+ var status = mavLinkMessage . ToStructure < MAVLink . mavlink_uavionix_adsb_out_status_t > ( ) ;
3399
+
3400
+ xpdr_es1090_tx_enabled = ( status . state & 128 ) != 0 ;
3401
+ xpdr_mode_S_enabled = ( status . state & 64 ) != 0 ;
3402
+ xpdr_mode_C_enabled = ( status . state & 32 ) != 0 ;
3403
+ xpdr_mode_A_enabled = ( status . state & 16 ) != 0 ;
3404
+ xpdr_ident_active = ( status . state & 8 ) != 0 ;
3405
+ xpdr_x_bit_status = ( status . state & 4 ) != 0 ;
3406
+ xpdr_interrogated_since_last = ( status . state & 2 ) != 0 ;
3407
+ xpdr_airborne_status = ( status . state & 1 ) != 0 ;
3408
+
3409
+ xpdr_mode_A_squawk_code = status . squawk ;
3410
+ xpdr_nic = ( byte ) ( status . NIC_NACp & 0x0F ) ;
3411
+ xpdr_nacp = ( byte ) ( ( status . NIC_NACp >> 4 ) & 0x0F ) ;
3412
+ xpdr_board_temperature = status . boardTemp ;
3413
+
3414
+ xpdr_maint_req = ( status . fault & 128 ) != 0 ;
3415
+ xpdr_adsb_tx_sys_fail = ( status . fault & 64 ) != 0 ;
3416
+ xpdr_gps_unavail = ( status . fault & 32 ) != 0 ;
3417
+ xpdr_gps_no_fix = ( status . fault & 16 ) != 0 ;
3418
+ xpdr_status_unavail = ( status . fault & 8 ) != 0 ;
3419
+
3420
+ xpdr_flight_id = status . flight_id ;
3421
+
3422
+ xpdr_status_pending = true ;
3423
+ }
3424
+ break ;
3337
3425
}
3338
3426
}
3339
3427
}
0 commit comments