#ifndef LIVOX_DEFINE_H_
#define LIVOX_DEFINE_H_
#include <stdio.h>
#include <string>
#include <memory>
#include <functional>
#include <vector>
#include <atomic>
#include "livox_lidar_def.h"
namespace livox {
namespace lidar {
#pragma pack(1)
const uint16_t KDefaultTimeOut = 1000;
static const uint32_t kMaxCommandBufferSize = 1400;
typedef struct {
std::string lidar_ipaddr;
std::string lidar_subnet_mask;
std::string lidar_gateway;
uint16_t cmd_data_port;
uint16_t push_msg_port;
uint16_t point_data_port;
uint16_t imu_data_port;
uint16_t log_data_port;
} LivoxLidarNetInfo;
typedef struct {
std::string host_ip;
std::string multicast_ip;
uint16_t cmd_data_port;
uint16_t push_msg_port;
uint16_t point_data_port;
uint16_t imu_data_port;
uint16_t log_data_port;
} HostNetInfo;
typedef struct {
std::vector<uint16_t> cmd_key_set;
} GeneralCfgInfo;
typedef struct {
uint8_t device_type;
LivoxLidarNetInfo lidar_net_info;
HostNetInfo host_net_info;
GeneralCfgInfo general_cfg_info;
} LivoxLidarCfg;
typedef struct {
bool lidar_log_enable;
uint64_t lidar_log_cache_size;
std::string lidar_log_path;
} LivoxLidarLoggerCfg;
typedef struct {
bool master_sdk;
} LivoxLidarSdkFrameworkCfg;
typedef enum {
kCommandIDLidarSearch = 0x0000,
kCommandIDLidarWorkModeControl = 0x0100,
kCommandIDLidarGetInternalInfo = 0x0101,
kCommandIDLidarPushMsg = 0x0102,
kCommandIDLidarRebootDevice = 0x0200,
kCommandIDLidarResetDevice = 0x0201,
kCommandIDLidarSetPPSSync = 0x0202,
kCommandIDLidarPushLog = 0x0300,
kCommandIDLidarCollectionLog = 0x0301,
kCommandIDLidarLogSysTimeSync = 0x0302,
kCommandIDLidarDebugPointCloudControl = 0x0303,
kCommandIDGeneralRequestUpgrade = 0x0400,
kCommandIDGeneralXferFirmware = 0x0401,
kCommandIDGeneralCompleteXferFirmware = 0x0402,
kCommandIDGeneralRequestUpgradeProgress = 0x0403,
kCommandIDGeneralRequestFirmwareInfo = 0xFF,
kCommandIDLidarCommandCount
} LidarCommandID;
typedef enum {
kCommandTypeCmd = 0,
kCommandTypeAck = 1,
} CommandType;
typedef enum {
kHostSend = 0,
kLidarSend = 1,
} SendType;
typedef struct {
uint8_t ret_code;
uint8_t dev_type;
char sn[16];
uint8_t lidar_ip[4];
uint16_t cmd_port;
} DetectionData;
typedef struct {
uint32_t handle;
uint16_t cmd_port;
uint8_t dev_type;
std::atomic<bool> is_get={false};
std::atomic<bool> is_set={false};
} ViewDevice;
typedef struct {
uint32_t handle;
uint8_t dev_type;
std::string host_ip;
uint16_t lidar_cmd_port;
uint16_t lidar_point_port;
uint16_t lidar_imu_data_port;
uint16_t host_point_port;
uint16_t host_imu_data_port;
} ViewLidarIpInfo;
typedef struct {
uint8_t lidar_ipaddr[4];
uint8_t lidar_subnet_mask[4];
uint8_t lidar_gateway[4];
} LivoxLidarIpInfoValue;
typedef struct {
uint8_t host_ip[4];
uint16_t host_port;
uint16_t lidar_port;
} HostIpInfoValue;
static const uint16_t kDetectionPort = 56000;
static const uint16_t kDetectionListenPort = 56001;
static const uint16_t kHostDebugPointCloudPort = 44332;
static const uint16_t kHAPCmdPort = 56000;
static const uint16_t kHAPPushMsgPort = 56000;
static const uint16_t kHAPPointDataPort = 57000;
static const uint16_t kHAPIMUPort = 58000;
static const uint16_t kHAPLogPort = 59000;
static const uint16_t kHAPDebugPointCloudPort = 60000;
static const uint16_t kLogPort = 0;
static const uint16_t kHAPLidarCmdPort = 56000;
static const uint16_t kMid360LidarCmdPort = 56100;
static const uint16_t kMid360LidarPushMsgPort = 56200;
static const uint16_t kMid360LidarPointCloudPort = 56300;
static const uint16_t kMid360LidarImuDataPort = 56400;
static const uint16_t kMid360LidarLogPort = 56500;
static const uint16_t kMid360LidarDebugPointCloudPort = 60301;
static const uint16_t kMid360HostCmdPort = 56101;
static const uint16_t kMid360HostPushMsgPort = 56201;
static const uint16_t kMid360HostPointCloudPort = 56301;
static const uint16_t kMid360HostImuDataPort = 56401;
static const uint16_t kMid360HostLogPort = 56501;
static const uint16_t kPaLidarCmdPort = 9347;
static const uint16_t kPaLidarPointCloudPort = 10000;
static const uint16_t kPaLidarFaultPort = 10001;
static const uint16_t kPaLidarLogPort = 1002;
static const uint16_t kPaHostFaultPort = 42867;
typedef enum {
kCmd = 0,
kPush = 1,
kPointCloud = 2,
kImuData = 3,
kLog = 4,
kFault = 5
} HostSocketType;
typedef enum {
kLidarCmdPort = 56100,
kLidarPushCmdPort = 56200,
kLidarPointDataPort = 56300,
kLidarImuDataPort = 56400,
kLidarLogPort = 56500
} LidarPort;
typedef struct {
uint8_t log_type;
uint8_t enable;
} EnableDeviceLoggerRequest;
typedef struct {
std::string sn;
uint8_t dev_type;
std::string lidar_ip;
uint16_t cmd_port;
} LidarDeviceInfo;
typedef struct {
uint8_t log_type; uint8_t file_index; uint8_t file_num;
uint8_t flag;
uint32_t timestamp;
uint16_t rsvd;
uint32_t trans_index;
uint16_t data_length; uint8_t data[1]; } DeviceLoggerFilePushRequest;
typedef struct {
uint8_t ret_code; uint8_t log_type; uint8_t file_index; uint32_t trans_index; } DeviceLoggerFilePushReponse;
enum class Flag : uint8_t {
kNull,
kCreateFile,
kEndFile,
kTransferData
};
using DataCallback = std::function<void(const uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket *data, void *client_data)>;
using LidarInfoCallback = std::function<void(const uint32_t, const uint8_t, const char*, void*)>;
typedef struct {
uint8_t firmware_type;
uint8_t encrypt_type;
uint32_t firmware_length;
uint8_t dev_type;
} LivoxLidarStartUpgradeRequest;
typedef struct {
uint8_t firmware_type;
uint8_t encrypt_type;
uint32_t firmware_length;
uint8_t dev_type;
uint32_t firmware_version;
uint64_t firmware_buildtime;
uint8_t hw_whitelist[32];
} LivoxLidarStartUpgradeRequestV3;
typedef struct {
uint8_t ret_code;
} LivoxLidarStartUpgradeResponse;
typedef struct {
uint32_t offset;
uint32_t length;
uint8_t encrypt_type;
uint8_t rsvd[3];
uint8_t data[1];
} LivoxLidarXferFirmwareResquest;
typedef struct {
uint8_t ret_code;
uint32_t offset;
uint32_t length;
} LivoxLidarXferFirmwareResponse;
typedef struct {
uint8_t checksum_type;
uint8_t checksum_length;
uint8_t checksum[1];
} LivoxLidarCompleteXferFirmwareResquest;
typedef struct {
uint8_t ret_code;
} LivoxLidarCompleteXferFirmwareResponse;
typedef struct {
uint8_t ret_code;
uint8_t progress;
} LivoxLidarGetUpgradeProgressResponse;
typedef struct {
uint8_t ret_code;
uint16_t length;
uint8_t info[1];
} LivoxLidarRequestFirmwareInfoResponse;
typedef struct {
uint8_t file_ver;
uint8_t dev_type;
uint8_t data_type;
uint8_t sn[16];
uint8_t rsvd[107];
uint16_t crc16;
} LivoxLidarDebugPointCloudFileHeader;
typedef struct {
uint8_t enable;
uint8_t host_ip_addr[4];
uint16_t host_port;
uint16_t bandwidth;
} LivoxLidarDebugPointCloudRequest;
typedef struct {
enum class SyncTimeType : uint8_t {
kRmcSyncTime = 2,
} type;
uint64_t ns;
} LivoxLidarRmcSyncTimeRequest;
typedef void(*LivoxLidarStartUpgradeCallback)(livox_status status, uint32_t handle,
LivoxLidarStartUpgradeResponse* response, void* client_data);
typedef void(*LivoxLidarXferFirmwareCallback)(livox_status status, uint32_t handle,
LivoxLidarXferFirmwareResponse* response, void* client_data);
typedef void(*LivoxLidarCompleteXferFirmwareCallback)(livox_status status, uint32_t handle,
LivoxLidarCompleteXferFirmwareResponse* response, void* client_data);
typedef void(*LivoxLidarGetUpgradeProgressCallback)(livox_status status,
uint32_t handle, LivoxLidarGetUpgradeProgressResponse* response, void* client_data);
typedef void(*LivoxLidarRequestFirmwareInfoCallback)(livox_status status,
uint32_t handle, LivoxLidarRequestFirmwareInfoResponse* response, void* client_data);
#pragma pack()
} }
# endif