-
Notifications
You must be signed in to change notification settings - Fork 70
/
main.cpp
215 lines (183 loc) · 7.81 KB
/
main.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
//
// The MIT License (MIT)
//
// Copyright (c) 2022 Livox. All rights reserved.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
//
#include "livox_lidar_def.h"
#include "livox_lidar_api.h"
#ifdef _WIN32
#include <winsock2.h>
#else
#include <unistd.h>
#include <arpa/inet.h>
#endif
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <thread>
#include <chrono>
#include <iostream>
void PointCloudCallback(uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket* data, void* client_data) {
if (data == nullptr) {
return;
}
printf("point cloud handle: %u, data_num: %d, data_type: %d, length: %d, frame_counter: %d\n",
handle, data->dot_num, data->data_type, data->length, data->frame_cnt);
if (data->data_type == kLivoxLidarCartesianCoordinateHighData) {
LivoxLidarCartesianHighRawPoint *p_point_data = (LivoxLidarCartesianHighRawPoint *)data->data;
for (uint32_t i = 0; i < data->dot_num; i++) {
//p_point_data[i].x;
//p_point_data[i].y;
//p_point_data[i].z;
}
}
else if (data->data_type == kLivoxLidarCartesianCoordinateLowData) {
LivoxLidarCartesianLowRawPoint *p_point_data = (LivoxLidarCartesianLowRawPoint *)data->data;
} else if (data->data_type == kLivoxLidarSphericalCoordinateData) {
LivoxLidarSpherPoint* p_point_data = (LivoxLidarSpherPoint *)data->data;
}
}
void ImuDataCallback(uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket* data, void* client_data) {
if (data == nullptr) {
return;
}
printf("Imu data callback handle:%u, data_num:%u, data_type:%u, length:%u, frame_counter:%u.\n",
handle, data->dot_num, data->data_type, data->length, data->frame_cnt);
}
// void OnLidarSetIpCallback(livox_vehicle_status status, uint32_t handle, uint8_t ret_code, void*) {
// if (status == kVehicleStatusSuccess) {
// printf("lidar set ip slot: %d, ret_code: %d\n",
// slot, ret_code);
// } else if (status == kVehicleStatusTimeout) {
// printf("lidar set ip number timeout\n");
// }
// }
void WorkModeCallback(livox_status status, uint32_t handle,LivoxLidarAsyncControlResponse *response, void *client_data) {
if (response == nullptr) {
return;
}
printf("WorkModeCallack, status:%u, handle:%u, ret_code:%u, error_key:%u",
status, handle, response->ret_code, response->error_key);
}
void RebootCallback(livox_status status, uint32_t handle, LivoxLidarRebootResponse* response, void* client_data) {
if (response == nullptr) {
return;
}
printf("RebootCallback, status:%u, handle:%u, ret_code:%u",
status, handle, response->ret_code);
}
void SetIpInfoCallback(livox_status status, uint32_t handle, LivoxLidarAsyncControlResponse *response, void *client_data) {
if (response == nullptr) {
return;
}
printf("LivoxLidarIpInfoCallback, status:%u, handle:%u, ret_code:%u, error_key:%u",
status, handle, response->ret_code, response->error_key);
if (response->ret_code == 0 && response->error_key == 0) {
LivoxLidarRequestReboot(handle, RebootCallback, nullptr);
}
}
void QueryInternalInfoCallback(livox_status status, uint32_t handle,
LivoxLidarDiagInternalInfoResponse* response, void* client_data) {
if (status != kLivoxLidarStatusSuccess) {
printf("Query lidar internal info failed.\n");
QueryLivoxLidarInternalInfo(handle, QueryInternalInfoCallback, nullptr);
return;
}
if (response == nullptr) {
return;
}
uint8_t host_point_ipaddr[4] {0};
uint16_t host_point_port = 0;
uint16_t lidar_point_port = 0;
uint8_t host_imu_ipaddr[4] {0};
uint16_t host_imu_data_port = 0;
uint16_t lidar_imu_data_port = 0;
uint16_t off = 0;
for (uint8_t i = 0; i < response->param_num; ++i) {
LivoxLidarKeyValueParam* kv = (LivoxLidarKeyValueParam*)&response->data[off];
if (kv->key == kKeyLidarPointDataHostIpCfg) {
memcpy(host_point_ipaddr, &(kv->value[0]), sizeof(uint8_t) * 4);
memcpy(&(host_point_port), &(kv->value[4]), sizeof(uint16_t));
memcpy(&(lidar_point_port), &(kv->value[6]), sizeof(uint16_t));
} else if (kv->key == kKeyLidarImuHostIpCfg) {
memcpy(host_imu_ipaddr, &(kv->value[0]), sizeof(uint8_t) * 4);
memcpy(&(host_imu_data_port), &(kv->value[4]), sizeof(uint16_t));
memcpy(&(lidar_imu_data_port), &(kv->value[6]), sizeof(uint16_t));
}
off += sizeof(uint16_t) * 2;
off += kv->length;
}
printf("Host point cloud ip addr:%u.%u.%u.%u, host point cloud port:%u, lidar point cloud port:%u.\n",
host_point_ipaddr[0], host_point_ipaddr[1], host_point_ipaddr[2], host_point_ipaddr[3], host_point_port, lidar_point_port);
printf("Host imu ip addr:%u.%u.%u.%u, host imu port:%u, lidar imu port:%u.\n",
host_imu_ipaddr[0], host_imu_ipaddr[1], host_imu_ipaddr[2], host_imu_ipaddr[3], host_imu_data_port, lidar_imu_data_port);
}
void LidarInfoChangeCallback(const uint32_t handle, const LivoxLidarInfo* info, void* client_data) {
if (info == nullptr) {
printf("lidar info change callback failed, the info is nullptr.\n");
return;
}
printf("LidarInfoChangeCallback Lidar handle: %u SN: %s\n", handle, info->sn);
// set the work mode to kLivoxLidarNormal, namely start the lidar
SetLivoxLidarWorkMode(handle, kLivoxLidarNormal, WorkModeCallback, nullptr);
QueryLivoxLidarInternalInfo(handle, QueryInternalInfoCallback, nullptr);
// LivoxLidarIpInfo lidar_ip_info;
// strcpy(lidar_ip_info.ip_addr, "192.168.1.10");
// strcpy(lidar_ip_info.net_mask, "255.255.255.0");
// strcpy(lidar_ip_info.gw_addr, "192.168.1.1");
// SetLivoxLidarLidarIp(handle, &lidar_ip_info, SetIpInfoCallback, nullptr);
}
void LivoxLidarPushMsgCallback(const uint32_t handle, const uint8_t dev_type, const char* info, void* client_data) {
struct in_addr tmp_addr;
tmp_addr.s_addr = handle;
std::cout << "handle: " << handle << ", ip: " << inet_ntoa(tmp_addr) << ", push msg info: " << std::endl;
std::cout << info << std::endl;
return;
}
int main(int argc, const char *argv[]) {
if (argc != 2) {
printf("Params Invalid, must input config path.\n");
return -1;
}
const std::string path = argv[1];
// REQUIRED, to init Livox SDK2
if (!LivoxLidarSdkInit(path.c_str())) {
printf("Livox Init Failed\n");
LivoxLidarSdkUninit();
return -1;
}
// REQUIRED, to get point cloud data via 'PointCloudCallback'
SetLivoxLidarPointCloudCallBack(PointCloudCallback, nullptr);
// OPTIONAL, to get imu data via 'ImuDataCallback'
// some lidar types DO NOT contain an imu component
SetLivoxLidarImuDataCallback(ImuDataCallback, nullptr);
SetLivoxLidarInfoCallback(LivoxLidarPushMsgCallback, nullptr);
// REQUIRED, to get a handle to targeted lidar and set its work mode to NORMAL
SetLivoxLidarInfoChangeCallback(LidarInfoChangeCallback, nullptr);
#ifdef WIN32
Sleep(300000);
#else
sleep(300);
#endif
LivoxLidarSdkUninit();
printf("Livox Quick Start Demo End!\n");
return 0;
}