37 int str_len = strlen(path_str);
47 if (timestamp_type == kTimestampTypePps) {
48 return timestamp.
stamp;
49 }
else if (timestamp_type == kTimestampTypeNoSync) {
50 return timestamp.
stamp;
51 }
else if (timestamp_type == kTimestampTypePtp) {
52 return timestamp.
stamp;
53 }
else if (timestamp_type == kTimestampTypePpsGps) {
55 time_utc.tm_isdst = 0;
64 uint64_t time_epoch = timegm(&time_utc);
66 time_epoch = time_epoch * 1000;
70 printf(
"Timestamp type[%d] invalid.\n", timestamp_type);
76 LivoxEthPacket *raw_packet =
77 reinterpret_cast<LivoxEthPacket *
>(packet->
raw_data);
79 memcpy(timestamp.
stamp_bytes, raw_packet->timestamp,
sizeof(timestamp));
81 if (raw_packet->timestamp_type == kTimestampTypePps) {
85 return timestamp.
stamp;
87 }
else if (raw_packet->timestamp_type == kTimestampTypeNoSync) {
88 return timestamp.
stamp;
89 }
else if (raw_packet->timestamp_type == kTimestampTypePtp) {
90 return timestamp.
stamp;
91 }
else if (raw_packet->timestamp_type == kTimestampTypePpsGps) {
93 time_utc.tm_isdst = 0;
94 time_utc.tm_year = raw_packet->timestamp[0] + 100;
95 time_utc.tm_mon = raw_packet->timestamp[1] - 1;
96 time_utc.tm_mday = raw_packet->timestamp[2];
97 time_utc.tm_hour = raw_packet->timestamp[3];
102 uint64_t time_epoch = timegm(&time_utc);
104 time_epoch = time_epoch * 1000;
108 printf(
"Timestamp type[%d] invalid.\n", raw_packet->timestamp_type);
118 queue_size = queue_size * 2;
129 std::vector<std::string> &bd_code_list) {
130 char *strs =
new char[strlen(cammandline_str) + 1];
131 strcpy(strs, cammandline_str);
133 std::string pattern =
"&";
134 char *bd_str = strtok(strs, pattern.c_str());
135 std::string invalid_bd =
"000000000";
136 while (bd_str != NULL) {
137 printf(
"Commandline input bd:%s\n", bd_str);
139 (NULL == strstr(bd_str, invalid_bd.c_str()))) {
140 bd_code_list.push_back(bd_str);
142 printf(
"Invalid bd:%s!\n", bd_str);
144 bd_str = strtok(NULL, pattern.c_str());
151 double cos_roll = cos(static_cast<double>(euler[0]));
152 double cos_pitch = cos(static_cast<double>(euler[1]));
153 double cos_yaw = cos(static_cast<double>(euler[2]));
154 double sin_roll = sin(static_cast<double>(euler[0]));
155 double sin_pitch = sin(static_cast<double>(euler[1]));
156 double sin_yaw = sin(static_cast<double>(euler[2]));
158 matrix[0][0] = cos_pitch * cos_yaw;
159 matrix[0][1] = sin_roll * sin_pitch * cos_yaw - cos_roll * sin_yaw;
160 matrix[0][2] = cos_roll * sin_pitch * cos_yaw + sin_roll * sin_yaw;
162 matrix[1][0] = cos_pitch * sin_yaw;
163 matrix[1][1] = sin_roll * sin_pitch * sin_yaw + cos_roll * cos_yaw;
164 matrix[1][2] = cos_roll * sin_pitch * sin_yaw - sin_roll * cos_yaw;
166 matrix[2][0] = -sin_pitch;
167 matrix[2][1] = sin_roll * cos_pitch;
168 matrix[2][2] = cos_roll * cos_pitch;
195 dst_point->
x = src_point.
x * extrinsic.
rotation[0][0] +
198 dst_point->
y = src_point.
x * extrinsic.
rotation[1][0] +
201 dst_point->
z = src_point.
x * extrinsic.
rotation[2][0] +
212 LivoxPoint *raw_point =
reinterpret_cast<LivoxPoint *
>(eth_packet->data);
214 while (points_per_packet) {
217 raw_point->y, raw_point->z)) {
235 LivoxRawPoint *raw_point =
236 reinterpret_cast<LivoxRawPoint *
>(eth_packet->data);
238 while (points_per_packet) {
241 raw_point->y, raw_point->z)) {
260 LivoxSpherPoint *raw_point =
261 reinterpret_cast<LivoxSpherPoint *
>(eth_packet->data);
263 while (points_per_packet) {
265 if (extrinsic.
enable && raw_point->depth) {
284 LivoxExtendRawPoint *raw_point =
285 reinterpret_cast<LivoxExtendRawPoint *
>(eth_packet->data);
288 while (points_per_packet) {
291 raw_point->y, raw_point->z)) {
295 dst_point->
tag = raw_point->tag;
297 dst_point->
line = line_id % line_num;
315 LivoxExtendSpherPoint *raw_point =
316 reinterpret_cast<LivoxExtendSpherPoint *
>(eth_packet->data);
319 while (points_per_packet) {
321 if (extrinsic.
enable && raw_point->depth) {
325 dst_point->
tag = raw_point->tag;
327 dst_point->
line = line_id % line_num;
345 LivoxExtendRawPoint *raw_point =
346 reinterpret_cast<LivoxExtendRawPoint *
>(eth_packet->data);
349 points_per_packet = points_per_packet * 2;
351 while (points_per_packet) {
354 raw_point->y, raw_point->z)) {
358 dst_point->
tag = raw_point->tag;
360 dst_point->
line = (line_id / 2) % line_num;
378 LivoxDualExtendSpherPoint *raw_point =
379 reinterpret_cast<LivoxDualExtendSpherPoint *
>(eth_packet->data);
382 while (points_per_packet) {
385 (LivoxDualExtendSpherPoint *)raw_point);
386 if (extrinsic.
enable && raw_point->depth1) {
390 dst_point->
tag = raw_point->tag1;
392 dst_point->
line = line_id % line_num;
398 if (extrinsic.
enable && raw_point->depth2) {
402 dst_point->
tag = raw_point->tag2;
404 dst_point->
line = line_id % line_num;
423 LivoxExtendRawPoint *raw_point =
424 reinterpret_cast<LivoxExtendRawPoint *
>(eth_packet->data);
427 points_per_packet = points_per_packet * 3;
429 while (points_per_packet) {
432 raw_point->y, raw_point->z)) {
436 dst_point->
tag = raw_point->tag;
438 dst_point->
line = (line_id / 3) % line_num;
456 LivoxTripleExtendSpherPoint *raw_point =
457 reinterpret_cast<LivoxTripleExtendSpherPoint *
>(eth_packet->data);
460 while (points_per_packet) {
464 (LivoxTripleExtendSpherPoint *)raw_point);
465 if (extrinsic.
enable && raw_point->depth1) {
469 dst_point->
tag = raw_point->tag1;
471 dst_point->
line = line_id % line_num;
477 if (extrinsic.
enable && raw_point->depth2) {
481 dst_point->
tag = raw_point->tag2;
483 dst_point->
line = line_id % line_num;
489 if (extrinsic.
enable && raw_point->depth3) {
493 dst_point->
tag = raw_point->tag3;
495 dst_point->
line = line_id % line_num;
510 memcpy(point_buf, eth_packet->data,
sizeof(LivoxImuPoint));
527 if (data_type < kMaxPointDataType)
528 return to_pxyzi_handler_table[data_type];
534 LivoxEthPacket *raw_packet =
535 reinterpret_cast<LivoxEthPacket *
>(storage_packet->
raw_data);
537 memset(raw_packet->data, 0, point_length * storage_packet->
point_num);
542 static void PointCloudConvert(LivoxPoint *p_dpoint, LivoxRawPoint *p_raw_point) {
543 p_dpoint->x = p_raw_point->x/1000.0f;
544 p_dpoint->y = p_raw_point->y/1000.0f;
545 p_dpoint->z = p_raw_point->z/1000.0f;
546 p_dpoint->reflectivity = p_raw_point->reflectivity;
554 buffer_time_ms_(buffer_time_ms), data_src_(data_src), request_exit_(false) {
605 if (data_size && (data_size >
lidars_[i].onetime_publish_packets)) {
617 return kDeviceTypeHub;
622 LivoxEthPacket* eth_packet) {
626 eth_packet->data_type);
631 printf(
"Lidar[%d][%s] DataType[%d] PacketInterval[%d] PublishPackets[%d]\n",
643 memcpy(cur_timestamp.
stamp_bytes, eth_packet->timestamp,
644 sizeof(cur_timestamp));
645 timestamp =
RawLdsStampToNs(cur_timestamp, eth_packet->timestamp_type);
647 printf(
"Raw EthPacket time out of range Lidar[%d]\n", handle);
651 if (kImu != eth_packet->data_type) {
653 if (eth_packet->timestamp_type == kTimestampTypePps) {
657 auto cur_time = std::chrono::high_resolution_clock::now();
658 int64_t sync_time = cur_time.time_since_epoch().count();
660 packet_statistic->
timebase = sync_time;
670 printf(
"Lidar[%d][%s] storage queue size : %d %d\n", p_lidar->
handle,
671 p_lidar->
info.broadcast_code, queue_size, p_queue->
size);
685 if (eth_packet->timestamp_type == kTimestampTypePps) {
689 auto cur_time = std::chrono::high_resolution_clock::now();
690 int64_t sync_time = cur_time.time_since_epoch().count();
701 printf(
"Lidar[%d][%s] imu storage queue size : %d %d\n", p_lidar->
handle,
702 p_lidar->
info.broadcast_code, queue_size, p_queue->
size);
bool IsFilePathValid(const char *path_str)
const uint32_t kMaxEthPacketQueueSize
const uint32_t kMaxSourceLidar
bool IsTripleFloatNoneZero(float x, float y, float z)
uint8_t raw_data[KEthPacketMaxLength]
void ParseCommandlineInputBdCode(const char *cammandline_str, std::vector< std::string > &bd_code_list)
Lds(uint32_t buffer_time_ms, uint8_t data_src)
int64_t last_imu_timestamp
uint32_t QueueIsFull(LidarDataQueue *queue)
float RotationMatrix[3][3]
uint32_t GetPointsPerPacket(uint32_t data_type)
uint8_t * LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet)
struct livox_ros::LdsStamp::@14 stamp_word
uint8_t *(* PointConvertHandler)(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
void ZeroPointDataOfStoragePacket(StoragePacket *storage_packet)
static uint8_t * LivoxRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
static uint8_t * LivoxTripleExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
static void ResetLidar(LidarDevice *lidar, uint8_t data_src)
static uint8_t * LivoxExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
uint32_t GetPacketNumPerSec(uint32_t product_type, uint32_t data_type)
uint32_t QueuePushAny(LidarDataQueue *queue, uint8_t *data, uint32_t length, uint64_t time_rcv, uint32_t point_num)
uint8_t GetDeviceType(uint8_t handle)
void PointExtrisincCompensation(PointXyz *dst_point, const PointXyz &src_point, ExtrinsicParameter &extrinsic)
volatile bool request_exit_
bool IsAllQueueReadStop()
uint64_t GetStoragePacketTimestamp(StoragePacket *packet, uint8_t data_src)
static uint8_t * LivoxDualExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
unsigned __int64 uint64_t
virtual void PrepareExit(void)
const int64_t kPacketTimeGap
const uint64_t kRosTimeMax
void RawPointConvert(LivoxPointXyzr *dst_point, LivoxPoint *raw_point)
uint32_t QueueUsedSize(LidarDataQueue *queue)
LidarPacketStatistic statistic_info
int InitQueue(LidarDataQueue *queue, uint32_t queue_size)
volatile uint32_t packet_interval
uint32_t GetPacketInterval(uint32_t product_type, uint32_t data_type)
StoragePacket * storage_packet
uint32_t QueueIsEmpty(LidarDataQueue *queue)
void StorageRawPacket(uint8_t handle, LivoxEthPacket *eth_packet)
uint64_t RawLdsStampToNs(LdsStamp ×tamp, uint8_t timestamp_type)
const int kPathStrMaxSize
static uint8_t * LivoxDualExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
static uint8_t * LivoxSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
void UpdateLidarInfoByEthPacket(LidarDevice *p_lidar, LivoxEthPacket *eth_packet)
const int kPathStrMinSize
void EulerAnglesToRotationMatrix(EulerAngle euler, RotationMatrix matrix)
static uint8_t * LivoxTripleExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
static uint8_t * LivoxExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
int DeInitQueue(LidarDataQueue *queue)
void ResetLds(uint8_t data_src)
bool IsTripleIntNoneZero(int32_t x, int32_t y, int32_t z)
const uint32_t kMinEthPacketQueueSize
const PointConvertHandler to_pxyzi_handler_table[kMaxPointDataType]
uint8_t * LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
LidarDevice lidars_[kMaxSourceLidar]
volatile uint32_t onetime_publish_packets
uint32_t GetEthPacketLen(uint32_t data_type)
PointConvertHandler GetConvertHandler(uint8_t data_type)
static void SetLidarDataSrc(LidarDevice *lidar, uint8_t data_src)
uint32_t CalculatePacketQueueSize(uint32_t interval_ms, uint8_t product_type, uint8_t data_type)
volatile LidarConnectState connect_state
volatile uint32_t packet_interval_max
uint32_t GetPointLen(uint32_t data_type)