/* Copyright (C) 2019 Intel Corporation SPDX-License-Identifier: Apache-2.0 Open Drone ID C Library Maintainer: Gabriel Cox gabriel.c.cox@intel.com */ /*整体来看国标是开源标准的阉割板 系统报文略有区别 缺少认证报文、操作源ID识别报文*/ /*民航轻微小型无人驾驶航空器试运行*/ #pragma once #include #include #define CNDID_MESSAGE_SIZE 25 // 单报文字节大小 #define CNDID_ID_SIZE 20 // USA ID 长度 #define CNDID_STR_SIZE 23 // 描述字符串长度 #define CNDID_PROTOCOL_VERSION 1 // UAS 报文版本 #ifndef CNDID_BASIC_ID_MAX_MESSAGES #define CNDID_BASIC_ID_MAX_MESSAGES 2 // 可手动设置ID个数 #endif #if (CNDID_BASIC_ID_MAX_MESSAGES < 1) || (CNDID_BASIC_ID_MAX_MESSAGES > 5) #error "CNDID_BASIC_ID_MAX_MESSAGES must be between 1 and 5." #endif #define CNDID_PACK_MAX_MESSAGES 10 // 最多打包10条报文 #define CNDID_SUCCESS 0 #define CNDID_FAIL 1 #define CN_MIN_DIR 0 // Minimum direction #define CN_MAX_DIR 360 // Maximum direction #define CN_INV_DIR 361 // Invalid direction #define CN_MIN_SPEED_H 0 // Minimum speed horizontal #define CN_MAX_SPEED_H 254.25f // Maximum speed horizontal #define CN_INV_SPEED_H 255 // Invalid speed horizontal #define CN_MIN_SPEED_V (-62) // Minimum speed vertical #define CN_MAX_SPEED_V 62 // Maximum speed vertical #define CN_INV_SPEED_V 63 // Invalid speed vertical #define CN_MIN_LAT (-90) // Minimum latitude #define CN_MAX_LAT 90 // Maximum latitude #define CN_MIN_LON (-180) // Minimum longitude #define CN_MAX_LON 180 // Maximum longitude #define CN_MIN_ALT (-1000) // Minimum altitude #define CN_MAX_ALT 31767.5f// Maximum altitude #define CN_INV_ALT CN_MIN_ALT // Invalid altitude #define CN_MAX_TIMESTAMP (60 * 60) #define CN_INV_TIMESTAMP 0xFFFF // Invalid, No Value or Unknown Timestamp #define CN_MAX_AREA_RADIUS 2550 #define CN_COORD_TYPE 0 // #define COORDTYPE 1 // #define COORDTYPE 2 // #define COORDTYPE 3 // 消息类型枚举 typedef enum CNDID_messagetype { CNDID_MESSAGETYPE_BASIC_ID = 0, CNDID_MESSAGETYPE_LOCATION = 1, // CNDID_MESSAGETYPE_RVS1 = 2, CNDID_MESSAGETYPE_SELF_ID = 3, CNDID_MESSAGETYPE_SYSTEM = 4, // CNDID_MESSAGETYPE_RVS2 = 5, CNDID_MESSAGETYPE_PACKED = 0xF, CNDID_MESSAGETYPE_INVALID = 0xFF, } CNDID_MessageType_t; // 每种消息类型都必须维护其自身的消息uint8_t计数器。 // 如果消息内容发生变化,该计数器必须递增。对于相同消息内容的重复传输, // 计数器的递增是可选的。 typedef enum CNDID_msg_counter { CNDID_MSG_COUNTER_BASIC_ID = 0, CNDID_MSG_COUNTER_LOCATION = 1, // CNDID_MSG_COUNTER_RVS1 = 2, CNDID_MSG_COUNTER_SELF_ID = 3, CNDID_MSG_COUNTER_SYSTEM = 4, // CNDID_MSG_COUNTER_RVS2 = 5, CNDID_MSG_COUNTER_PACKED = 6, CNDID_MSG_COUNTER_AMOUNT = 7, } CNDID_MsgCounter_t; /***************************************0x0 ID报文*******************************************/ // ID类型 ASTMF3411-22a标准的表5 typedef enum CNDID_idtype { CNDID_IDTYPE_NONE = 0, CNDID_IDTYPE_SERIAL_NUMBER = 1, CNDID_IDTYPE_CAA_REGISTRATION_ID = 2, // 民航局 CNDID_IDTYPE_UTM_ASSIGNED_UUID = 3, // 无人机系统(UAS,即无人驾驶航空器系统)交通管理 CNDID_IDTYPE_SPECIFIC_SESSION_ID = 4, // 确切的id类型由UASID的第一个字节指定,这些类型 // 这些值由国际民用航空组织(ICAO)管理。0 被保留。1 - 224 由国际民用航空组织(ICAO)管理。 // 225 - 255 仅可用于私人实验用途 // 5 to 15 reserved } CNDID_IDType_t; // UA 类型 typedef enum CNDID_uatype { CNDID_UATYPE_NONE = 0, CNDID_UATYPE_AEROPLANE = 1, // Fixed wing CNDID_UATYPE_HELICOPTER_OR_MULTIROTOR = 2, CNDID_UATYPE_GYROPLANE = 3, CNDID_UATYPE_HYBRID_LIFT = 4, // Fixed wing aircraft that can take off vertically CNDID_UATYPE_ORNITHOPTER = 5, CNDID_UATYPE_GLIDER = 6, CNDID_UATYPE_KITE = 7, CNDID_UATYPE_FREE_BALLOON = 8, CNDID_UATYPE_CAPTIVE_BALLOON = 9, CNDID_UATYPE_AIRSHIP = 10, // Such as a blimp CNDID_UATYPE_FREE_FALL_PARACHUTE = 11, // Unpowered CNDID_UATYPE_ROCKET = 12, CNDID_UATYPE_TETHERED_POWERED_AIRCRAFT = 13, CNDID_UATYPE_GROUND_OBSTACLE = 14, CNDID_UATYPE_OTHER = 15, } CNDID_UAType_t; typedef struct CNDID_BasicID_data { CNDID_UAType_t UAType; CNDID_IDType_t IDType; char UASID[CNDID_ID_SIZE+1]; // 额外的字节用于在标准形式中容纳空终止符。用NULL填充未使用的空间 } CNDID_BasicID_data; /** * @Name CNDID_PackedStructs * 为广播准备的压缩数据结构 * 最好不要直接访问这些数据。请使用编码器/解码器。 */ typedef struct __attribute__((__packed__)) CNDID_BasicID_encoded { // Byte 0 [MessageType][ProtoVersion] -- must define LSb first uint8_t ProtoVersion: 4; uint8_t MessageType : 4; // Byte 1 [IDType][UAType] -- must define LSb first uint8_t UAType: 4; uint8_t IDType: 4; // Bytes 2-21 char UASID[CNDID_ID_SIZE]; // 22-23 char Reserved[3]; } CNDID_BasicID_encoded; /***************************************0x1 向量报文*******************************************/ // 状态 ASTMF3411-22a标准的表6 typedef enum CNDID_status { CNDID_STATUS_UNDECLARED = 0, CNDID_STATUS_GROUND = 1, CNDID_STATUS_AIRBORNE = 2, CNDID_STATUS_EMERGENCY = 3, CNDID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4, // 3 to 15 reserved } CNDID_Status_t; // 高度类型 typedef enum CNDID_Height_reference { CNDID_HEIGHT_REF_OVER_TAKEOFF = 0, CNDID_HEIGHT_REF_OVER_GROUND = 1, } CNDID_HeightReference_t; // 水平精度 typedef enum CNDID_Horizontal_accuracy { CNDID_HOR_ACC_UNKNOWN = 0, CNDID_HOR_ACC_10NM = 1, // Nautical Miles. 18.52 km CNDID_HOR_ACC_4NM = 2, // 7.408 km CNDID_HOR_ACC_2NM = 3, // 3.704 km CNDID_HOR_ACC_1NM = 4, // 1.852 km CNDID_HOR_ACC_0_5NM = 5, // 926 m CNDID_HOR_ACC_0_3NM = 6, // 555.6 m CNDID_HOR_ACC_0_1NM = 7, // 185.2 m CNDID_HOR_ACC_0_05NM = 8, // 92.6 m CNDID_HOR_ACC_30_METER = 9, CNDID_HOR_ACC_10_METER = 10, CNDID_HOR_ACC_3_METER = 11, CNDID_HOR_ACC_1_METER = 12, // 13 to 15 reserved } CNDID_HorizontalAccuracy_t; // 垂直精度 typedef enum CNDID_Vertical_accuracy { CNDID_VER_ACC_UNKNOWN = 0, CNDID_VER_ACC_150_METER = 1, CNDID_VER_ACC_45_METER = 2, CNDID_VER_ACC_25_METER = 3, CNDID_VER_ACC_10_METER = 4, CNDID_VER_ACC_3_METER = 5, CNDID_VER_ACC_1_METER = 6, // 7 to 15 reserved } CNDID_VerticalAccuracy_t; // 速度精度 typedef enum CNDID_Speed_accuracy { CNDID_SPEED_ACC_UNKNOWN = 0, CNDID_SPEED_ACC_10_METERS_PER_SECOND = 1, CNDID_SPEED_ACC_3_METERS_PER_SECOND = 2, CNDID_SPEED_ACC_1_METERS_PER_SECOND = 3, CNDID_SPEED_ACC_0_3_METERS_PER_SECOND = 4, // 5 to 15 reserved } CNDID_SpeedAccuracy_t; // 时间戳精度 typedef enum CNDID_Timestamp_accuracy { CNDID_TIME_ACC_UNKNOWN = 0, CNDID_TIME_ACC_0_1_SECOND = 1, CNDID_TIME_ACC_0_2_SECOND = 2, CNDID_TIME_ACC_0_3_SECOND = 3, CNDID_TIME_ACC_0_4_SECOND = 4, CNDID_TIME_ACC_0_5_SECOND = 5, CNDID_TIME_ACC_0_6_SECOND = 6, CNDID_TIME_ACC_0_7_SECOND = 7, CNDID_TIME_ACC_0_8_SECOND = 8, CNDID_TIME_ACC_0_9_SECOND = 9, CNDID_TIME_ACC_1_0_SECOND = 10, CNDID_TIME_ACC_1_1_SECOND = 11, CNDID_TIME_ACC_1_2_SECOND = 12, CNDID_TIME_ACC_1_3_SECOND = 13, CNDID_TIME_ACC_1_4_SECOND = 14, CNDID_TIME_ACC_1_5_SECOND = 15, } CNDID_TimeStampAccuracy_t; typedef struct CNDID_Location_data { CNDID_Status_t Status; // 状态 float Direction; // 度数。0 ≤ x < 360。基于真北的航线航向。无效、无值或未知:361度 float SpeedHorizontal; // 米/秒。仅为正值。无效、无值或未知:255米/秒。如果速度≥254.25米/秒:254.25米/秒 float SpeedVertical; // 米/秒。无效、无值或未知:63米/秒。如果速度≥62米/秒:62米/秒 double Latitude; // 无效、无值或未知:0度(纬度/经度均为0度) double Longitude; // 无效、无值或未知:0度(纬度/经度均为0度) float AltitudeBaro; // 米(参考值29.92英寸汞柱,1013.24毫巴)。无效、无值或未知:-1000米 float AltitudeGeo; // 米(WGS84 - HAE)。无效、无值或未知:-1000米 CNDID_HeightReference_t HeightType; float Height; // 米。无效、无值或未知:-1000米 CNDID_HorizontalAccuracy_t HorizAccuracy; CNDID_VerticalAccuracy_t VertAccuracy; CNDID_VerticalAccuracy_t BaroAccuracy; CNDID_SpeedAccuracy_t SpeedAccuracy; CNDID_TimeStampAccuracy_t TSAccuracy; float TimeStamp; // 相对于UTC的整点过后的秒数。无效、无值或未知:0xFFFF } CNDID_Location_data; // byte 0 是报头 typedef struct __attribute__((__packed__)) CNDID_Location_encoded { // Byte 0 [MessageType][ProtoVersion] -- must define LSb first uint8_t ProtoVersion: 4; uint8_t MessageType : 4; // Byte 1 -- 必须先定义 低位 uint8_t SpeedMult: 1; uint8_t EWDirection: 1; uint8_t HeightType: 1; uint8_t Reserved: 1; uint8_t Status: 4; // Bytes 2-17 uint8_t Direction; uint8_t SpeedHorizontal; int8_t SpeedVertical; int32_t Latitude; int32_t Longitude; uint16_t AltitudeBaro; uint16_t AltitudeGeo; uint16_t Height; // Byte 19 [VertAccuracy][HorizAccuracy] -- must define LSb first 国标的PDF这里有错误 uint8_t HorizAccuracy:4; uint8_t VertAccuracy:4; // Byte 20 [BaroAccuracy][SpeedAccuracy] -- must define LSb first uint8_t SpeedAccuracy:4; uint8_t BaroAccuracy:4; // Byte 21-22 uint16_t TimeStamp; // Byte 23 [Reserved2][TSAccuracy] -- must define LSb first uint8_t TSAccuracy:4; uint8_t Reserved2:4; // Byte 24 char Reserved3; } CNDID_Location_encoded; /***************************************0x3 运行描述报文*******************************************/ // 行为描述 0x3报文 可选 typedef enum { CNDID_OPERATOR_ID = 0, // 文字描述 // 1 to 200 reserved // 201 to 255 available for private use } CNDID_DescType_t; typedef struct CNDID_SelfID_data { CNDID_DescType_t DescType; char Desc[CNDID_STR_SIZE+1]; // 额外的字节用于在标准形式中容纳空终止符。用NULL填充未使用的空间。 } CNDID_SelfID_data; // 字节0是报文头 typedef struct __attribute__((__packed__)) CNDID_SelfID_encoded { // Byte 0 [MessageType][ProtoVersion] -- must define LSb first uint8_t ProtoVersion: 4; uint8_t MessageType : 4; // Byte 1 uint8_t DescType; // Byte 2-24 char Desc[CNDID_STR_SIZE]; } CNDID_SelfID_encoded; /***************************************0x4 系统报文*******************************************/ // 坐标系类型 typedef enum { CNDID_COORD_TYPE_WGS84 = 0x00, // 00:WGS-84坐标系(GPS/北斗通用,国标默认) CNDID_COORD_TYPE_GCJ02 = 0x01, // 01:GCJ-02火星坐标系(中国国测局加密) CNDID_COORD_TYPE_BD09 = 0x02, // 10:BD-09坐标系(北斗专用) CNDID_COORD_TYPE_CGCS2000 = 0x03, // 11:CGCS2000国家大地坐标系(中国新一代) } CNDID_CoordType_t; // 等级分类归属区域 typedef enum { CNDID_CLASSIFICATION_TYPE_UNDECLARED = 0, CNDID_CLASSIFICATION_TYPE_EU = 1, // European Union CNDID_CLASSIFICATION_TYPE_CN = 2, // 中国 // 2 to 7 reserved } CNDID_classification_type_t; // 控制站位置类型 typedef enum CNDID_operator_location_type { CNDID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0, // Takeoff location and altitude CNDID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1, // Dynamic/Live location and altitude CNDID_OPERATOR_LOCATION_TYPE_FIXED = 2, // Fixed location and altitude // 3 to 255 reserved } CNDID_operator_location_type_t; // UA运行类别定义 typedef enum { CNDID_CATA_CN_UNDEFINED = 0x00, // 未定义 CNDID_CATA_CN_OPEN = 0x01, // 开放类 CNDID_CATA_CN_SPECIAL = 0x02, // 特许类 CNDID_CATA_CN_CERTIFIED = 0x03 // 审定类 } CNDID_category_CN_t; // 无人机等级 typedef enum { CNDID_CLASS_CN_MICRO = 0, // 微型无人机 CNDID_CLASS_CN_LIGHT = 1, // 轻型无人机 CNDID_CLASS_CN_SMALL = 2, // 小型无人机 CNDID_CLASS_CN_IDF_OTHER = 3, // 可识别的其他类型 } CNDID_class_CN_t; typedef struct CNDID_System_data { CNDID_CoordType_t Coord_Type; // 坐标系类型 多出来的 国际是保留的 CNDID_classification_type_t Classification_Type; // 所属区域 CNDID_operator_location_type_t OperatorLocationType; // 控制站位置类型 double OperatorLatitude; // 无效、无值或未知:0度(纬度/经度均为0度) double OperatorLongitude; // 无效、无值或未知:0度(纬度/经度均为0度) uint16_t AreaCount; // 默认值 1 uint16_t AreaRadius; // 米。默认值为0 float AreaCeiling; // 米。无效、无值或未知:-1000米 float AreaFloor; // 米。无效、无值或未知:-1000米 CNDID_category_CN_t CategoryCN; // 仅在ClassificationType = CNDID_CLASSIFICATION_TYPE_CN 时填写 CNDID_class_CN_t ClassCN; // 仅在ClassificationType = CNDID_CLASSIFICATION_TYPE_CN 时填写 float OperatorAltitudeGeo; // 米(WGS84-HAE)。无效、无值或未知:-1000米 uint32_t Timestamp; // 相对于2019年1月1日世界标准时间/ Unix时间00:00:00 } CNDID_System_data; // byte 0 是报头 typedef struct __attribute__((__packed__)) CNDID_System_encoded { // Byte 0 [MessageType][ProtoVersion] -- must define LSb first uint8_t ProtoVersion: 4; uint8_t MessageType : 4; // Byte 1 -- must define LSb first uint8_t OperatorLocationType: 2; uint8_t ClassificationType : 3; uint8_t CoordType :2; // 坐标系类型 uint8_t Reserved: 1; // Byte 2-9 int32_t OperatorLatitude; int32_t OperatorLongitude; // Byte 10-16 uint16_t AreaCount; uint8_t AreaRadius; uint16_t AreaCeiling; uint16_t AreaFloor; // Byte 17 [CategoryCN][ClassCN] -- must define LSb first uint8_t ClassCN: 4; uint8_t CategoryCN: 4; // Byte 18-23 uint16_t OperatorAltitudeGeo; uint32_t Timestamp; // Byte 24 char Reserved2; } CNDID_System_encoded; /***************************************0xF 打包报文*******************************************/ /* * 从联合成员的任何结构部分访问前两个字段(即ProtoVersion和MessageType)都是安全的, *因为这些字段的声明是相同的,并且位于结构的开头部分。 *ISO/IEC 9899:1999第6.5.2.3部分第5条及相关的示例3对此进行了规定。 https://www.iso.org/standard/29237.html */ typedef union CNDID_Message_encoded { uint8_t rawData[CNDID_MESSAGE_SIZE]; // 一份报文25字节 CNDID_BasicID_encoded basicId; CNDID_Location_encoded location; CNDID_SelfID_encoded selfId; CNDID_System_encoded system; } CNDID_Message_encoded; typedef struct __attribute__((__packed__)) CNDID_MessagePack_encoded { // Byte 0 [MessageType][ProtoVersion] -- must define LSb first uint8_t ProtoVersion: 4; uint8_t MessageType : 4; // Byte 1 - 2 uint8_t SingleMessageSize; // 每个报文长度 uint8_t MsgPackSize; // 报文数量 // Byte 3 - 227 CNDID_Message_encoded Messages[CNDID_PACK_MAX_MESSAGES]; } CNDID_MessagePack_encoded; typedef struct CNDID_MessagePack_data { uint8_t SingleMessageSize; // Must always be CNDID_MESSAGE_SIZE uint8_t MsgPackSize; // Number of messages in pack (NOT number of bytes) CNDID_Message_encoded Messages[CNDID_PACK_MAX_MESSAGES]; } CNDID_MessagePack_data; /*********************************************************************************************/ typedef struct CNDID_UAS_Data { CNDID_BasicID_data BasicID[CNDID_BASIC_ID_MAX_MESSAGES]; // 基础ID 2个ID报文??? CNDID_Location_data Location; // 位置向量 CNDID_SelfID_data SelfID; // 运行描述 CNDID_System_data System; // 系统 uint8_t BasicIDValid[CNDID_BASIC_ID_MAX_MESSAGES]; // 基础ID非法 uint8_t LocationValid; // 位置非法 uint8_t SelfIDValid; // 运行描述非法 uint8_t SystemValid; // 系统非法 } CNDID_UAS_Data; // API Calls void cndid_initBasicIDData(CNDID_BasicID_data *data); void cndid_initLocationData(CNDID_Location_data *data); void cndid_initSelfIDData(CNDID_SelfID_data *data); void cndid_initSystemData(CNDID_System_data *data); void cndid_initMessagePackData(CNDID_MessagePack_data *data); void cndid_initUasData(CNDID_UAS_Data *data); int encodeCNBasicIDMessage(CNDID_BasicID_encoded *outEncoded, CNDID_BasicID_data *inData); int encodeCNLocationMessage(CNDID_Location_encoded *outEncoded, CNDID_Location_data *inData); int encodeCNSelfIDMessage(CNDID_SelfID_encoded *outEncoded, CNDID_SelfID_data *inData); int encodeCNSystemMessage(CNDID_System_encoded *outEncoded, CNDID_System_data *inData); int encodeCNMessagePack(CNDID_MessagePack_encoded *outEncoded, CNDID_MessagePack_data *inData); int decodeCNBasicIDMessage(CNDID_BasicID_data *outData, CNDID_BasicID_encoded *inEncoded); int decodeCNLocationMessage(CNDID_Location_data *outData, CNDID_Location_encoded *inEncoded); int decodeCNSelfIDMessage(CNDID_SelfID_data *outData, CNDID_SelfID_encoded *inEncoded); int decodeCNSystemMessage(CNDID_System_data *outData, CNDID_System_encoded *inEncoded); int decodeCNMessagePack(CNDID_UAS_Data *uasData, CNDID_MessagePack_encoded *pack); int getCNBasicIDType(CNDID_BasicID_encoded *inEncoded, enum CNDID_idtype *idType); CNDID_MessageType_t decodeCNMessageType(uint8_t byte); CNDID_MessageType_t decodeCNDroneID(CNDID_UAS_Data *uas_data, uint8_t *msg_data); // Helper Functions CNDID_HorizontalAccuracy_t createCNEnumHorizontalAccuracy(float Accuracy); CNDID_VerticalAccuracy_t createCNEnumVerticalAccuracy(float Accuracy); CNDID_SpeedAccuracy_t createCNEnumSpeedAccuracy(float Accuracy); CNDID_TimeStampAccuracy_t createCNEnumTimestampAccuracy(float Accuracy); float decodeCNHorizontalAccuracy(CNDID_HorizontalAccuracy_t Accuracy); float decodeCNVerticalAccuracy(CNDID_VerticalAccuracy_t Accuracy); float decodeCNSpeedAccuracy(CNDID_SpeedAccuracy_t Accuracy); float decodeCNTimestampAccuracy(CNDID_TimeStampAccuracy_t Accuracy); // CN DroneID WiFi functions /** * cndid_message_build_pack - 组合消息并对cndid数据包进行编码 * @UAS_Data:无人机的一般状态信息 * @pack:要写入的缓冲区空间 * @buflen:缓冲区空间的最大长度 * * Returns length on success, < 0 on failure. @buf only contains a valid message * if the return code is >0 */ int cndid_message_build_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen); /* cndid_wifi_build_nan_sync_beacon_frame - 创建一个NAN同步信标帧 * 该帧应在NAN动作帧之前发送。 * @mac:将发送NAN帧的wifi适配器的mac地址 * @buf:指向将写入NAN的缓冲区空间的指针 * * @buf_size:缓冲区的最大大小 * Returns the packet length on success, or < 0 on error. */ int cndid_wifi_build_nan_sync_beacon_frame(char *mac, uint8_t *buf, size_t buf_size); /* cndid_wifi_build_message_pack_nan_action_frame - 创建一个消息包 * 包含来自无人机信息的每种类型的消息,将其放入一个NAN动作帧中。 * @UAS_Data:无人机的一般状态信息 * @mac:将发送NAN帧的WiFi适配器的mac地址 * @send_counter:序列号,每次调用此函数时需递增 * @buf:指向将写入NAN的缓冲区空间的指针 * @buf_size:缓冲区的最大大小 * * Returns the packet length on success, or < 0 on error. */ int cndid_wifi_build_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data, char *mac, uint8_t send_counter, uint8_t *buf, size_t buf_size); /* cndid_wifi_build_message_pack_beacon_frame - 创建一个消息包 * 将来自无人机信息的每种类型的消息整合到一个信标帧中。 * @UAS_Data:无人机的一般状态信息 * @mac:将发送信标帧的WiFi适配器的MAC地址 * @SSID:要发送的WiFi网络的服务集标识符 * @SSID_len:服务集标识符字符串的字节长度 * @interval_tu:WiFi时间单位中的信标间隔 * @send_counter:序列号,每次调用此函数时需递增 * @buf:指向将写入信标帧的缓冲区空间的指针 * @buf_size:缓冲区的最大大小 * * Returns the packet length on success, or < 0 on error. */ int cndid_wifi_build_message_pack_beacon_frame(CNDID_UAS_Data *UAS_Data, char *mac, const char *SSID, size_t SSID_len, uint16_t interval_tu, uint8_t send_counter, uint8_t *buf, size_t buf_size); /* cndid_message_process_pack - 从cndid消息包中解码消息 * @UAS_Data:无人机的一般状态信息 * @pack:要从中读取的缓冲区空间 * @buflen:缓冲区空间的长度 * * Returns 0 on success */ int cndid_message_process_pack(CNDID_UAS_Data *UAS_Data, uint8_t *pack, size_t buflen); /* cndid_wifi_receive_message_pack_nan_action_frame - 处理接收到的消息包 * 将来自无人机信息的每种类型的消息转换为NAN动作帧 * @UAS_Data:无人机的一般状态信息 * @mac:将发送NAN帧的WiFi适配器的MAC地址 * @buf:存储NAN的缓冲区空间指针 * @buf_size:缓冲区的最大大小 * * Returns 0 on success, or < 0 on error. Will fill 6 bytes into @mac. */ int cndid_wifi_receive_message_pack_nan_action_frame(CNDID_UAS_Data *UAS_Data, char *mac, uint8_t *buf, size_t buf_size); #ifndef CNDID_DISABLE_PRINTF void PrintByteArray(uint8_t *byteArray, uint16_t asize, int spaced); void PrintBasicID_data(CNDID_BasicID_data *BasicID); void PrintLocation_data(CNDID_Location_data *Location); void PrintSelfID_data(CNDID_SelfID_data *SelfID); void PrintSystem_data(CNDID_System_data *System_data); #endif // CNDID_DISABLE_PRINTF