interface ParsedMAVLinkMessage$1 {
    timestamp: number;
    system_id: number;
    component_id: number;
    message_id: number;
    message_name: string;
    sequence: number;
    payload: Record<string, unknown>;
    protocol_version: 1 | 2;
    checksum: number;
    crc_ok: boolean;
    signature?: Uint8Array;
    dialect?: string;
}

declare enum MAV_AUTOPILOTEnum {
    MAV_AUTOPILOT_GENERIC = 0,
    MAV_AUTOPILOT_RESERVED = 1,
    MAV_AUTOPILOT_SLUGS = 2,
    MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
    MAV_AUTOPILOT_OPENPILOT = 4,
    MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
    MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
    MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
    MAV_AUTOPILOT_INVALID = 8,
    MAV_AUTOPILOT_PPZ = 9,
    MAV_AUTOPILOT_UDB = 10,
    MAV_AUTOPILOT_FP = 11,
    MAV_AUTOPILOT_PX4 = 12,
    MAV_AUTOPILOT_SMACCMPILOT = 13,
    MAV_AUTOPILOT_AUTOQUAD = 14,
    MAV_AUTOPILOT_ARMAZILA = 15,
    MAV_AUTOPILOT_AEROB = 16,
    MAV_AUTOPILOT_ASLUAV = 17,
    MAV_AUTOPILOT_SMARTAP = 18,
    MAV_AUTOPILOT_AIRRAILS = 19,
    MAV_AUTOPILOT_REFLEX = 20
}
type MAV_AUTOPILOT = MAV_AUTOPILOTEnum;
declare enum MAV_TYPEEnum {
    MAV_TYPE_GENERIC = 0,
    MAV_TYPE_FIXED_WING = 1,
    MAV_TYPE_QUADROTOR = 2,
    MAV_TYPE_COAXIAL = 3,
    MAV_TYPE_HELICOPTER = 4,
    MAV_TYPE_ANTENNA_TRACKER = 5,
    MAV_TYPE_GCS = 6,
    MAV_TYPE_AIRSHIP = 7,
    MAV_TYPE_FREE_BALLOON = 8,
    MAV_TYPE_ROCKET = 9,
    MAV_TYPE_GROUND_ROVER = 10,
    MAV_TYPE_SURFACE_BOAT = 11,
    MAV_TYPE_SUBMARINE = 12,
    MAV_TYPE_HEXAROTOR = 13,
    MAV_TYPE_OCTOROTOR = 14,
    MAV_TYPE_TRICOPTER = 15,
    MAV_TYPE_FLAPPING_WING = 16,
    MAV_TYPE_KITE = 17,
    MAV_TYPE_ONBOARD_CONTROLLER = 18,
    MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
    MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
    MAV_TYPE_VTOL_TILTROTOR = 21,
    MAV_TYPE_VTOL_FIXEDROTOR = 22,
    MAV_TYPE_VTOL_TAILSITTER = 23,
    MAV_TYPE_VTOL_TILTWING = 24,
    MAV_TYPE_VTOL_RESERVED5 = 25,
    MAV_TYPE_GIMBAL = 26,
    MAV_TYPE_ADSB = 27,
    MAV_TYPE_PARAFOIL = 28,
    MAV_TYPE_DODECAROTOR = 29,
    MAV_TYPE_CAMERA = 30,
    MAV_TYPE_CHARGING_STATION = 31,
    MAV_TYPE_FLARM = 32,
    MAV_TYPE_SERVO = 33,
    MAV_TYPE_ODID = 34,
    MAV_TYPE_DECAROTOR = 35,
    MAV_TYPE_BATTERY = 36,
    MAV_TYPE_PARACHUTE = 37,
    MAV_TYPE_LOG = 38,
    MAV_TYPE_OSD = 39,
    MAV_TYPE_IMU = 40,
    MAV_TYPE_GPS = 41,
    MAV_TYPE_WINCH = 42,
    MAV_TYPE_GENERIC_MULTIROTOR = 43,
    MAV_TYPE_ILLUMINATOR = 44,
    MAV_TYPE_SPACECRAFT_ORBITER = 45,
    MAV_TYPE_GROUND_QUADRUPED = 46,
    MAV_TYPE_VTOL_GYRODYNE = 47,
    MAV_TYPE_GRIPPER = 48
}
type MAV_TYPE = MAV_TYPEEnum;
declare enum MAV_MODE_FLAGEnum {
    MAV_MODE_FLAG_SAFETY_ARMED = 128,
    MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
    MAV_MODE_FLAG_HIL_ENABLED = 32,
    MAV_MODE_FLAG_STABILIZE_ENABLED = 16,
    MAV_MODE_FLAG_GUIDED_ENABLED = 8,
    MAV_MODE_FLAG_AUTO_ENABLED = 4,
    MAV_MODE_FLAG_TEST_ENABLED = 2,
    MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
}
type MAV_MODE_FLAG = MAV_MODE_FLAGEnum;
declare enum MAV_MODE_FLAG_DECODE_POSITIONEnum {
    MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
    MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
    MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
    MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
    MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
    MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
    MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
    MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1
}
type MAV_MODE_FLAG_DECODE_POSITION = MAV_MODE_FLAG_DECODE_POSITIONEnum;
declare enum MAV_STATEEnum {
    MAV_STATE_UNINIT = 0,
    MAV_STATE_BOOT = 1,
    MAV_STATE_CALIBRATING = 2,
    MAV_STATE_STANDBY = 3,
    MAV_STATE_ACTIVE = 4,
    MAV_STATE_CRITICAL = 5,
    MAV_STATE_EMERGENCY = 6,
    MAV_STATE_POWEROFF = 7,
    MAV_STATE_FLIGHT_TERMINATION = 8
}
type MAV_STATE = MAV_STATEEnum;
declare enum MAV_COMPONENTEnum {
    MAV_COMP_ID_ALL = 0,
    MAV_COMP_ID_AUTOPILOT1 = 1,
    MAV_COMP_ID_USER1 = 25,
    MAV_COMP_ID_USER2 = 26,
    MAV_COMP_ID_USER3 = 27,
    MAV_COMP_ID_USER4 = 28,
    MAV_COMP_ID_USER5 = 29,
    MAV_COMP_ID_USER6 = 30,
    MAV_COMP_ID_USER7 = 31,
    MAV_COMP_ID_USER8 = 32,
    MAV_COMP_ID_USER9 = 33,
    MAV_COMP_ID_USER10 = 34,
    MAV_COMP_ID_USER11 = 35,
    MAV_COMP_ID_USER12 = 36,
    MAV_COMP_ID_USER13 = 37,
    MAV_COMP_ID_USER14 = 38,
    MAV_COMP_ID_USER15 = 39,
    MAV_COMP_ID_USER16 = 40,
    MAV_COMP_ID_USER17 = 41,
    MAV_COMP_ID_USER18 = 42,
    MAV_COMP_ID_USER19 = 43,
    MAV_COMP_ID_USER20 = 44,
    MAV_COMP_ID_USER21 = 45,
    MAV_COMP_ID_USER22 = 46,
    MAV_COMP_ID_USER23 = 47,
    MAV_COMP_ID_USER24 = 48,
    MAV_COMP_ID_USER25 = 49,
    MAV_COMP_ID_USER26 = 50,
    MAV_COMP_ID_USER27 = 51,
    MAV_COMP_ID_USER28 = 52,
    MAV_COMP_ID_USER29 = 53,
    MAV_COMP_ID_USER30 = 54,
    MAV_COMP_ID_USER31 = 55,
    MAV_COMP_ID_USER32 = 56,
    MAV_COMP_ID_USER33 = 57,
    MAV_COMP_ID_USER34 = 58,
    MAV_COMP_ID_USER35 = 59,
    MAV_COMP_ID_USER36 = 60,
    MAV_COMP_ID_USER37 = 61,
    MAV_COMP_ID_USER38 = 62,
    MAV_COMP_ID_USER39 = 63,
    MAV_COMP_ID_USER40 = 64,
    MAV_COMP_ID_USER41 = 65,
    MAV_COMP_ID_USER42 = 66,
    MAV_COMP_ID_USER43 = 67,
    MAV_COMP_ID_TELEMETRY_RADIO = 68,
    MAV_COMP_ID_USER45 = 69,
    MAV_COMP_ID_USER46 = 70,
    MAV_COMP_ID_USER47 = 71,
    MAV_COMP_ID_USER48 = 72,
    MAV_COMP_ID_USER49 = 73,
    MAV_COMP_ID_USER50 = 74,
    MAV_COMP_ID_USER51 = 75,
    MAV_COMP_ID_USER52 = 76,
    MAV_COMP_ID_USER53 = 77,
    MAV_COMP_ID_USER54 = 78,
    MAV_COMP_ID_USER55 = 79,
    MAV_COMP_ID_USER56 = 80,
    MAV_COMP_ID_USER57 = 81,
    MAV_COMP_ID_USER58 = 82,
    MAV_COMP_ID_USER59 = 83,
    MAV_COMP_ID_USER60 = 84,
    MAV_COMP_ID_USER61 = 85,
    MAV_COMP_ID_USER62 = 86,
    MAV_COMP_ID_USER63 = 87,
    MAV_COMP_ID_USER64 = 88,
    MAV_COMP_ID_USER65 = 89,
    MAV_COMP_ID_USER66 = 90,
    MAV_COMP_ID_USER67 = 91,
    MAV_COMP_ID_USER68 = 92,
    MAV_COMP_ID_USER69 = 93,
    MAV_COMP_ID_USER70 = 94,
    MAV_COMP_ID_USER71 = 95,
    MAV_COMP_ID_USER72 = 96,
    MAV_COMP_ID_USER73 = 97,
    MAV_COMP_ID_USER74 = 98,
    MAV_COMP_ID_USER75 = 99,
    MAV_COMP_ID_CAMERA = 100,
    MAV_COMP_ID_CAMERA2 = 101,
    MAV_COMP_ID_CAMERA3 = 102,
    MAV_COMP_ID_CAMERA4 = 103,
    MAV_COMP_ID_CAMERA5 = 104,
    MAV_COMP_ID_CAMERA6 = 105,
    MAV_COMP_ID_SERVO1 = 140,
    MAV_COMP_ID_SERVO2 = 141,
    MAV_COMP_ID_SERVO3 = 142,
    MAV_COMP_ID_SERVO4 = 143,
    MAV_COMP_ID_SERVO5 = 144,
    MAV_COMP_ID_SERVO6 = 145,
    MAV_COMP_ID_SERVO7 = 146,
    MAV_COMP_ID_SERVO8 = 147,
    MAV_COMP_ID_SERVO9 = 148,
    MAV_COMP_ID_SERVO10 = 149,
    MAV_COMP_ID_SERVO11 = 150,
    MAV_COMP_ID_SERVO12 = 151,
    MAV_COMP_ID_SERVO13 = 152,
    MAV_COMP_ID_SERVO14 = 153,
    MAV_COMP_ID_GIMBAL = 154,
    MAV_COMP_ID_LOG = 155,
    MAV_COMP_ID_ADSB = 156,
    MAV_COMP_ID_OSD = 157,
    MAV_COMP_ID_PERIPHERAL = 158,
    MAV_COMP_ID_QX1_GIMBAL = 159,
    MAV_COMP_ID_FLARM = 160,
    MAV_COMP_ID_PARACHUTE = 161,
    MAV_COMP_ID_WINCH = 169,
    MAV_COMP_ID_GIMBAL2 = 171,
    MAV_COMP_ID_GIMBAL3 = 172,
    MAV_COMP_ID_GIMBAL4 = 173,
    MAV_COMP_ID_GIMBAL5 = 174,
    MAV_COMP_ID_GIMBAL6 = 175,
    MAV_COMP_ID_BATTERY = 180,
    MAV_COMP_ID_BATTERY2 = 181,
    MAV_COMP_ID_MAVCAN = 189,
    MAV_COMP_ID_MISSIONPLANNER = 190,
    MAV_COMP_ID_ONBOARD_COMPUTER = 191,
    MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
    MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
    MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
    MAV_COMP_ID_PATHPLANNER = 195,
    MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
    MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
    MAV_COMP_ID_PAIRING_MANAGER = 198,
    MAV_COMP_ID_IMU = 200,
    MAV_COMP_ID_IMU_2 = 201,
    MAV_COMP_ID_IMU_3 = 202,
    MAV_COMP_ID_GPS = 220,
    MAV_COMP_ID_GPS2 = 221,
    MAV_COMP_ID_ODID_TXRX_1 = 236,
    MAV_COMP_ID_ODID_TXRX_2 = 237,
    MAV_COMP_ID_ODID_TXRX_3 = 238,
    MAV_COMP_ID_UDP_BRIDGE = 240,
    MAV_COMP_ID_UART_BRIDGE = 241,
    MAV_COMP_ID_TUNNEL_NODE = 242,
    MAV_COMP_ID_ILLUMINATOR = 243,
    MAV_COMP_ID_SYSTEM_CONTROL = 250
}
type MAV_COMPONENT = MAV_COMPONENTEnum;
declare enum MAV_BOOLEnum {
    MAV_BOOL_FALSE = 0,
    MAV_BOOL_TRUE = 1
}
type MAV_BOOL = MAV_BOOLEnum;

interface MessageHeartbeat {
    custom_mode: number;
    type: MAV_TYPE;
    autopilot: MAV_AUTOPILOT;
    base_mode: MAV_MODE_FLAG;
    system_status: MAV_STATE;
    mavlink_version: number;
}
interface MessageProtocolVersion {
    spec_version_hash: number[];
    library_version_hash: number[];
    version: number;
    min_version: number;
    max_version: number;
}
interface MessageTypeMap {
    HEARTBEAT: MessageHeartbeat;
    PROTOCOL_VERSION: MessageProtocolVersion;
}
type AnyMessage = ParsedMAVLinkMessage$1;
declare function isHeartbeat(msg: ParsedMAVLinkMessage$1): msg is ParsedMAVLinkMessage$1 & {
    payload: MessageHeartbeat;
};
declare function isProtocolVersion(msg: ParsedMAVLinkMessage$1): msg is ParsedMAVLinkMessage$1 & {
    payload: MessageProtocolVersion;
};

interface ParsedMAVLinkMessage {
    timestamp: number;
    system_id: number;
    component_id: number;
    message_id: number;
    message_name: string;
    sequence: number;
    payload: Record<string, unknown>;
    protocol_version: 1 | 2;
    checksum: number;
    crc_ok: boolean;
    signature?: Uint8Array;
    dialect?: string;
}
interface MAVLinkFrame {
    magic: number;
    length: number;
    incompatible_flags?: number;
    compatible_flags?: number;
    sequence: number;
    system_id: number;
    component_id: number;
    message_id: number;
    payload: Uint8Array;
    checksum: number;
    signature?: Uint8Array;
    crc_ok?: boolean;
    protocol_version?: 1 | 2;
}
interface MessageDefinition {
    id: number;
    name: string;
    fields: FieldDefinition[];
}
interface FieldDefinition {
    name: string;
    type: string;
    arrayLength?: number;
    extension?: boolean;
}
declare abstract class DialectParser {
    protected messageDefinitions: Map<number, MessageDefinition>;
    protected dialectName: string;
    private buffer;
    constructor(dialectName: string);
    abstract loadDefinitions(): Promise<void>;
    parseBytes(data: Uint8Array): ParsedMAVLinkMessage[];
    private tryParseFrame;
    resetBuffer(): void;
    decode(frame: MAVLinkFrame): ParsedMAVLinkMessage;
    private decodePayload;
    private getDefaultValue;
    private decodeField;
    private decodeSingleValue;
    getMessageDefinition(id: number): MessageDefinition | undefined;
    getSupportedMessageIds(): number[];
    getDialectName(): string;
    supportsMessage(messageId: number): boolean;
    serializeMessage(message: Record<string, unknown> & {
        message_name: string;
    }): Uint8Array;
    private extractMessageFields;
    private completeMessageWithDefaults;
    private getDefaultValueForField;
    private serializePayload;
    private serializeField;
    private serializeSingleValue;
    private getFieldSize;
    private getSingleFieldSize;
    private getDefaultValueForType;
    private createMAVLinkFrame;
}
declare class StandardParser extends DialectParser {
    constructor();
    loadDefinitions(): Promise<void>;
    private loadDefinitionsSync;
}
declare class StandardSerializer {
    private parser;
    constructor();
    serialize(message: Record<string, unknown> & {
        message_name: string;
    }): Uint8Array;
    completeMessage(message: Record<string, unknown> & {
        message_name: string;
    }): Record<string, unknown>;
    getSupportedMessages(): string[];
    supportsMessage(messageName: string): boolean;
}

export { MAV_AUTOPILOTEnum, MAV_BOOLEnum, MAV_COMPONENTEnum, MAV_MODE_FLAGEnum, MAV_MODE_FLAG_DECODE_POSITIONEnum, MAV_STATEEnum, MAV_TYPEEnum, StandardParser, StandardSerializer, isHeartbeat, isProtocolVersion };
export type { AnyMessage, MAV_AUTOPILOT, MAV_BOOL, MAV_COMPONENT, MAV_MODE_FLAG, MAV_MODE_FLAG_DECODE_POSITION, MAV_STATE, MAV_TYPE, MessageHeartbeat, MessageProtocolVersion, MessageTypeMap, ParsedMAVLinkMessage$1 as ParsedMAVLinkMessage };
