Documentation ¶
Index ¶
- Constants
- type Dialect
- type UavionixAdsbOutCfg
- func (m *UavionixAdsbOutCfg) GetCallsign() string
- func (m *UavionixAdsbOutCfg) GetDialect() string
- func (m *UavionixAdsbOutCfg) GetID() uint32
- func (m *UavionixAdsbOutCfg) GetMessageName() string
- func (m *UavionixAdsbOutCfg) GetVersion() int
- func (m *UavionixAdsbOutCfg) HasExtensionFields() bool
- func (m *UavionixAdsbOutCfg) Read(frame mavlink2.Frame) (err error)
- func (m *UavionixAdsbOutCfg) SetCallsign(input string) (err error)
- func (m *UavionixAdsbOutCfg) String() string
- func (m *UavionixAdsbOutCfg) Write(version int) (output []byte, err error)
- type UavionixAdsbOutDynamic
- func (m *UavionixAdsbOutDynamic) GetDialect() string
- func (m *UavionixAdsbOutDynamic) GetID() uint32
- func (m *UavionixAdsbOutDynamic) GetMessageName() string
- func (m *UavionixAdsbOutDynamic) GetVersion() int
- func (m *UavionixAdsbOutDynamic) HasExtensionFields() bool
- func (m *UavionixAdsbOutDynamic) Read(frame mavlink2.Frame) (err error)
- func (m *UavionixAdsbOutDynamic) String() string
- func (m *UavionixAdsbOutDynamic) Write(version int) (output []byte, err error)
- type UavionixAdsbTransceiverHealthReport
- func (m *UavionixAdsbTransceiverHealthReport) GetDialect() string
- func (m *UavionixAdsbTransceiverHealthReport) GetID() uint32
- func (m *UavionixAdsbTransceiverHealthReport) GetMessageName() string
- func (m *UavionixAdsbTransceiverHealthReport) GetVersion() int
- func (m *UavionixAdsbTransceiverHealthReport) HasExtensionFields() bool
- func (m *UavionixAdsbTransceiverHealthReport) Read(frame mavlink2.Frame) (err error)
- func (m *UavionixAdsbTransceiverHealthReport) String() string
- func (m *UavionixAdsbTransceiverHealthReport) Write(version int) (output []byte, err error)
Constants ¶
const ( /*UavionixAdsbOutDynamicStateIntentChange - */ UavionixAdsbOutDynamicStateIntentChange = 1 /*UavionixAdsbOutDynamicStateAutopilotEnabled - */ UavionixAdsbOutDynamicStateAutopilotEnabled = 2 /*UavionixAdsbOutDynamicStateNicbaroCrosschecked - */ UavionixAdsbOutDynamicStateNicbaroCrosschecked = 4 /*UavionixAdsbOutDynamicStateOnGround - */ UavionixAdsbOutDynamicStateOnGround = 8 /*UavionixAdsbOutDynamicStateIDent - */ UavionixAdsbOutDynamicStateIDent = 16 /*UavionixAdsbOutDynamicStateEnumEnd - */ UavionixAdsbOutDynamicStateEnumEnd = 17 )
UAVIONIX_ADSB_OUT_DYNAMIC_STATE - State flags for ADS-B transponder dynamic report
const ( /*UavionixAdsbOutRfSelectStandby - */ UavionixAdsbOutRfSelectStandby = 0 /*UavionixAdsbOutRfSelectRxEnabled - */ UavionixAdsbOutRfSelectRxEnabled = 1 /*UavionixAdsbOutRfSelectTxEnabled - */ UavionixAdsbOutRfSelectTxEnabled = 2 /*UavionixAdsbOutRfSelectEnumEnd - */ UavionixAdsbOutRfSelectEnumEnd = 3 )
UAVIONIX_ADSB_OUT_RF_SELECT - Transceiver RF control flags for ADS-B transponder dynamic reports
const ( /*UavionixAdsbOutDynamicGPSFixNone0 - */ UavionixAdsbOutDynamicGPSFixNone0 = 0 /*UavionixAdsbOutDynamicGPSFixNone1 - */ UavionixAdsbOutDynamicGPSFixNone1 = 1 /*UavionixAdsbOutDynamicGPSFix2D - */ UavionixAdsbOutDynamicGPSFix2D = 2 /*UavionixAdsbOutDynamicGPSFix3D - */ UavionixAdsbOutDynamicGPSFix3D = 3 /*UavionixAdsbOutDynamicGPSFixDGPS - */ UavionixAdsbOutDynamicGPSFixDGPS = 4 /*UavionixAdsbOutDynamicGPSFixRtk - */ UavionixAdsbOutDynamicGPSFixRtk = 5 /*UavionixAdsbOutDynamicGPSFixEnumEnd - */ UavionixAdsbOutDynamicGPSFixEnumEnd = 6 )
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX - Status for ADS-B transponder dynamic input
const ( /*UavionixAdsbRfHealthInitializing - */ UavionixAdsbRfHealthInitializing = 0 /*UavionixAdsbRfHealthOk - */ UavionixAdsbRfHealthOk = 1 /*UavionixAdsbRfHealthFailTx - */ UavionixAdsbRfHealthFailTx = 2 /*UavionixAdsbRfHealthFailRx - */ UavionixAdsbRfHealthFailRx = 16 /*UavionixAdsbRfHealthEnumEnd - */ UavionixAdsbRfHealthEnumEnd = 17 )
UAVIONIX_ADSB_RF_HEALTH - Status flags for ADS-B transponder dynamic output
const ( /*UavionixAdsbOutCfgAiRCraftSizeNoData - */ UavionixAdsbOutCfgAiRCraftSizeNoData = 0 /*UavionixAdsbOutCfgAiRCraftSizeL15MW23M - */ UavionixAdsbOutCfgAiRCraftSizeL15MW23M = 1 /*UavionixAdsbOutCfgAiRCraftSizeL25MW28P5M - */ UavionixAdsbOutCfgAiRCraftSizeL25MW28P5M = 2 /*UavionixAdsbOutCfgAiRCraftSizeL2534M - */ UavionixAdsbOutCfgAiRCraftSizeL2534M = 3 /*UavionixAdsbOutCfgAiRCraftSizeL3533M - */ UavionixAdsbOutCfgAiRCraftSizeL3533M = 4 /*UavionixAdsbOutCfgAiRCraftSizeL3538M - */ UavionixAdsbOutCfgAiRCraftSizeL3538M = 5 /*UavionixAdsbOutCfgAiRCraftSizeL4539P5M - */ UavionixAdsbOutCfgAiRCraftSizeL4539P5M = 6 /*UavionixAdsbOutCfgAiRCraftSizeL4545M - */ UavionixAdsbOutCfgAiRCraftSizeL4545M = 7 /*UavionixAdsbOutCfgAiRCraftSizeL5545M - */ UavionixAdsbOutCfgAiRCraftSizeL5545M = 8 /*UavionixAdsbOutCfgAiRCraftSizeL5552M - */ UavionixAdsbOutCfgAiRCraftSizeL5552M = 9 /*UavionixAdsbOutCfgAiRCraftSizeL6559P5M - */ UavionixAdsbOutCfgAiRCraftSizeL6559P5M = 10 /*UavionixAdsbOutCfgAiRCraftSizeL6567M - */ UavionixAdsbOutCfgAiRCraftSizeL6567M = 11 /*UavionixAdsbOutCfgAiRCraftSizeL75W72P5M - */ UavionixAdsbOutCfgAiRCraftSizeL75W72P5M = 12 /*UavionixAdsbOutCfgAiRCraftSizeL75W80M - */ UavionixAdsbOutCfgAiRCraftSizeL75W80M = 13 /*UavionixAdsbOutCfgAiRCraftSizeL85W80M - */ UavionixAdsbOutCfgAiRCraftSizeL85W80M = 14 /*UavionixAdsbOutCfgAiRCraftSizeL85W90M - */ UavionixAdsbOutCfgAiRCraftSizeL85W90M = 15 /*UavionixAdsbOutCfgAiRCraftSizeEnumEnd - */ UavionixAdsbOutCfgAiRCraftSizeEnumEnd = 16 )
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE - Definitions for aircraft size
const ( /*UavionixAdsbOutCfgGPSOffsetLatNoData - */ UavionixAdsbOutCfgGPSOffsetLatNoData = 0 /*UavionixAdsbOutCfgGPSOffsetLatLeft2M - */ UavionixAdsbOutCfgGPSOffsetLatLeft2M = 1 /*UavionixAdsbOutCfgGPSOffsetLatLeft4M - */ UavionixAdsbOutCfgGPSOffsetLatLeft4M = 2 /*UavionixAdsbOutCfgGPSOffsetLatLeft6M - */ UavionixAdsbOutCfgGPSOffsetLatLeft6M = 3 /*UavionixAdsbOutCfgGPSOffsetLatRight0M - */ UavionixAdsbOutCfgGPSOffsetLatRight0M = 4 /*UavionixAdsbOutCfgGPSOffsetLatRight2M - */ UavionixAdsbOutCfgGPSOffsetLatRight2M = 5 /*UavionixAdsbOutCfgGPSOffsetLatRight4M - */ UavionixAdsbOutCfgGPSOffsetLatRight4M = 6 /*UavionixAdsbOutCfgGPSOffsetLatRight6M - */ UavionixAdsbOutCfgGPSOffsetLatRight6M = 7 /*UavionixAdsbOutCfgGPSOffsetLatEnumEnd - */ UavionixAdsbOutCfgGPSOffsetLatEnumEnd = 8 )
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT - GPS lataral offset encoding
const ( /*UavionixAdsbOutCfgGPSOffsetLonNoData - */ UavionixAdsbOutCfgGPSOffsetLonNoData = 0 /*UavionixAdsbOutCfgGPSOffsetLonAppliedBySensor - */ UavionixAdsbOutCfgGPSOffsetLonAppliedBySensor = 1 /*UavionixAdsbOutCfgGPSOffsetLonEnumEnd - */ UavionixAdsbOutCfgGPSOffsetLonEnumEnd = 2 )
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON - GPS longitudinal offset encoding
const ( /*UavionixAdsbOutNoEmergency - */ UavionixAdsbOutNoEmergency = 0 /*UavionixAdsbOutGeneralEmergency - */ UavionixAdsbOutGeneralEmergency = 1 /*UavionixAdsbOutLifeguardEmergency - */ UavionixAdsbOutLifeguardEmergency = 2 /*UavionixAdsbOutMinIMUmFuelEmergency - */ UavionixAdsbOutMinIMUmFuelEmergency = 3 /*UavionixAdsbOutNoCommEmergency - */ UavionixAdsbOutNoCommEmergency = 4 /*UavionixAdsbOutUnlawfulInterferanceEmergency - */ UavionixAdsbOutUnlawfulInterferanceEmergency = 5 /*UavionixAdsbOutDownedAiRCraftEmergency - */ UavionixAdsbOutDownedAiRCraftEmergency = 6 /*UavionixAdsbOutReserved - */ UavionixAdsbOutReserved = 7 /*UavionixAdsbEmergencyStatusEnumEnd - */ UavionixAdsbEmergencyStatusEnumEnd = 8 )
UAVIONIX_ADSB_EMERGENCY_STATUS - Emergency status encoding
Variables ¶
This section is empty.
Functions ¶
This section is empty.
Types ¶
type Dialect ¶
type Dialect struct{}
Dialect represents a collection of MAVLink messages
func (Dialect) GetMessage ¶
GetMessage extracts and parses the message contained in the Frame
type UavionixAdsbOutCfg ¶
type UavionixAdsbOutCfg struct { /*Icao Vehicle address (24 bit) */ Icao uint32 /*Stallspeed Aircraft stall speed in cm/s */ Stallspeed uint16 /*Callsign Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only) */ Callsign [9]byte /*Emittertype Transmitting vehicle type. See ADSB_EMITTER_TYPE enum */ Emittertype uint8 /*AiRCraftsize Aircraft length and width encoding (table 2-35 of DO-282B) */ AiRCraftsize uint8 /*GPSoffsetlat GPS antenna lateral offset (table 2-36 of DO-282B) */ GPSoffsetlat uint8 /*GPSoffsetlon GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B) */ GPSoffsetlon uint8 /*Rfselect ADS-B transponder reciever and transmit enable flags */ Rfselect uint8 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
UavionixAdsbOutCfg Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter)
func (*UavionixAdsbOutCfg) GetCallsign ¶
func (m *UavionixAdsbOutCfg) GetCallsign() string
GetCallsign decodes the null-terminated string in the Callsign
func (*UavionixAdsbOutCfg) GetDialect ¶
func (m *UavionixAdsbOutCfg) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*UavionixAdsbOutCfg) GetID ¶
func (m *UavionixAdsbOutCfg) GetID() uint32
GetID gets the ID of the Message
func (*UavionixAdsbOutCfg) GetMessageName ¶
func (m *UavionixAdsbOutCfg) GetMessageName() string
GetMessageName gets the name of the Message
func (*UavionixAdsbOutCfg) GetVersion ¶
func (m *UavionixAdsbOutCfg) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*UavionixAdsbOutCfg) HasExtensionFields ¶
func (m *UavionixAdsbOutCfg) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*UavionixAdsbOutCfg) Read ¶
func (m *UavionixAdsbOutCfg) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*UavionixAdsbOutCfg) SetCallsign ¶
func (m *UavionixAdsbOutCfg) SetCallsign(input string) (err error)
SetCallsign encodes the input string to the Callsign array
func (*UavionixAdsbOutCfg) String ¶
func (m *UavionixAdsbOutCfg) String() string
type UavionixAdsbOutDynamic ¶
type UavionixAdsbOutDynamic struct { /*Utctime UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX */ Utctime uint32 /*GPSlat Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX */ GPSlat int32 /*GPSlon Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX */ GPSlon int32 /*GPSalt Altitude (WGS84). UP +ve. If unknown set to INT32_MAX */ GPSalt int32 /*Baroaltmsl Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX */ Baroaltmsl int32 /*Accuracyhor Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX */ Accuracyhor uint32 /*Accuracyvert Vertical accuracy in cm. If unknown set to UINT16_MAX */ Accuracyvert uint16 /*Accuracyvel Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX */ Accuracyvel uint16 /*Velvert GPS vertical speed in cm/s. If unknown set to INT16_MAX */ Velvert int16 /*Velns North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX */ Velns int16 /*Velew East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX */ Velew int16 /*State ADS-B transponder dynamic input state flags */ State uint16 /*Squawk Mode A code (typically 1200 [0x04B0] for VFR) */ Squawk uint16 /*GPSfix 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK */ GPSfix uint8 /*Numsats Number of satellites visible. If unknown set to UINT8_MAX */ Numsats uint8 /*Emergencystatus Emergency status */ Emergencystatus uint8 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
UavionixAdsbOutDynamic Dynamic data used to generate ADS-B out transponder data (send at 5Hz)
func (*UavionixAdsbOutDynamic) GetDialect ¶
func (m *UavionixAdsbOutDynamic) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*UavionixAdsbOutDynamic) GetID ¶
func (m *UavionixAdsbOutDynamic) GetID() uint32
GetID gets the ID of the Message
func (*UavionixAdsbOutDynamic) GetMessageName ¶
func (m *UavionixAdsbOutDynamic) GetMessageName() string
GetMessageName gets the name of the Message
func (*UavionixAdsbOutDynamic) GetVersion ¶
func (m *UavionixAdsbOutDynamic) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*UavionixAdsbOutDynamic) HasExtensionFields ¶
func (m *UavionixAdsbOutDynamic) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*UavionixAdsbOutDynamic) Read ¶
func (m *UavionixAdsbOutDynamic) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*UavionixAdsbOutDynamic) String ¶
func (m *UavionixAdsbOutDynamic) String() string
type UavionixAdsbTransceiverHealthReport ¶
type UavionixAdsbTransceiverHealthReport struct { /*Rfhealth ADS-B transponder messages */ Rfhealth uint8 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
UavionixAdsbTransceiverHealthReport Transceiver heartbeat with health report (updated every 10s)
func (*UavionixAdsbTransceiverHealthReport) GetDialect ¶
func (m *UavionixAdsbTransceiverHealthReport) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*UavionixAdsbTransceiverHealthReport) GetID ¶
func (m *UavionixAdsbTransceiverHealthReport) GetID() uint32
GetID gets the ID of the Message
func (*UavionixAdsbTransceiverHealthReport) GetMessageName ¶
func (m *UavionixAdsbTransceiverHealthReport) GetMessageName() string
GetMessageName gets the name of the Message
func (*UavionixAdsbTransceiverHealthReport) GetVersion ¶
func (m *UavionixAdsbTransceiverHealthReport) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*UavionixAdsbTransceiverHealthReport) HasExtensionFields ¶
func (m *UavionixAdsbTransceiverHealthReport) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*UavionixAdsbTransceiverHealthReport) Read ¶
func (m *UavionixAdsbTransceiverHealthReport) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*UavionixAdsbTransceiverHealthReport) String ¶
func (m *UavionixAdsbTransceiverHealthReport) String() string