39 #include "../dataunnpacker_commondef.h"
40 #include "../dataunpacker.h"
41 #include "../dataunnpacker_internal.h"
60 const _u64 channelBaudRate = timing.native_baudrate? timing.native_baudrate:115200;
66 tranmissionDelay = 100;
70 const _u64 sampleDelay = (timing.sample_duration_uS >> 1);
71 const _u64 sampleFilterDelay = timing.sample_duration_uS;
72 const _u64 groupingDelay = (31 - sampleIdx) * timing.sample_duration_uS;
75 return sampleFilterDelay + sampleDelay + tranmissionDelay + timing.linkage_delay_uS + groupingDelay;
79 UnpackerHandler_CapsuleNode::UnpackerHandler_CapsuleNode()
80 : _cached_scan_node_buf_pos(0)
81 , _is_previous_capsuledataRdy(false)
82 , _cached_last_data_timestamp_us(0)
109 for (
size_t pos = 0; pos < cnt; ++pos) {
114 _u8 tmp = (current_data >> 4);
127 _u8 tmp = (current_data >> 4);
148 _u8 recvChecksum = ((node->s_checksum_1 & 0xF) | (node->s_checksum_2 << 4));
155 if (recvChecksum == checksum)
160 #ifdef _CPU_ENDIAN_BIG
161 node->start_angle_sync_q6 =
le16_to_cpu(node->start_angle_sync_q6);
162 for (
size_t cpos = 0; cpos <
_countof(node->cabins); ++cpos) {
163 node->cabins[cpos].distance_angle_1 =
le16_to_cpu(node->cabins[cpos].distance_angle_1);
164 node->cabins[cpos].distance_angle_2 =
le16_to_cpu(node->cabins[cpos].distance_angle_2);
211 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
214 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
215 if (prevStartAngle_q8 > currentStartAngle_q8) {
216 diffAngle_q8 += (360 << 8);
219 int angleInc_q16 = (diffAngle_q8 << 3);
220 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
233 angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3 << 13)) >> 10);
234 syncBit[0] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
235 currentAngle_raw_q16 += angleInc_q16;
238 angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3 << 13)) >> 10);
239 syncBit[1] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
240 currentAngle_raw_q16 += angleInc_q16;
242 for (
int cpos = 0; cpos < 2; ++cpos) {
244 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
245 if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
250 hqNode.
flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
277 const _u64 channelBaudRate = timing.native_baudrate ? timing.native_baudrate : 256000;
283 tranmissionDelay = 100;
287 const _u64 sampleDelay = (timing.sample_duration_uS >> 1);
288 const _u64 sampleFilterDelay = timing.sample_duration_uS;
289 const _u64 groupingDelay = ((32 * 3 - 1) - sampleIdx) * timing.sample_duration_uS;
292 return sampleFilterDelay + sampleDelay + tranmissionDelay + timing.linkage_delay_uS + groupingDelay;
297 : _cached_scan_node_buf_pos(0)
298 , _is_previous_capsuledataRdy(false)
299 , _cached_last_data_timestamp_us(0)
327 for (
size_t pos = 0; pos < cnt; ++pos) {
332 _u8 tmp = (current_data >> 4);
345 _u8 tmp = (current_data >> 4);
366 _u8 recvChecksum = ((node->s_checksum_1 & 0xF) | (node->s_checksum_2 << 4));
373 if (recvChecksum == checksum)
378 #ifdef _CPU_ENDIAN_BIG
379 node->start_angle_sync_q6 =
le16_to_cpu(node->start_angle_sync_q6);
380 for (
size_t cpos = 0; cpos <
_countof(node->ultra_cabins); ++cpos) {
381 node->ultra_cabins[cpos].combined_x3 =
le32_to_cpu(node->ultra_cabins[cpos].combined_x3);
424 static const _u32 VBS_SCALED_BASE[] = {
432 static const _u32 VBS_SCALED_LVL[] = {
440 static const _u32 VBS_TARGET_BASE[] = {
448 for (
size_t i = 0; i <
_countof(VBS_SCALED_BASE); ++i)
450 int remain = ((int)scaled - (
int)VBS_SCALED_BASE[i]);
452 scaleLevel = VBS_SCALED_LVL[i];
453 return VBS_TARGET_BASE[i] + (remain << scaleLevel);
465 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
468 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
469 if (prevStartAngle_q8 > currentStartAngle_q8) {
470 diffAngle_q8 += (360 << 8);
473 int angleInc_q16 = (diffAngle_q8 << 3) / 3;
474 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
490 int dist_predict1 = (((int)(
combined_x3 << 10)) >> 22);
495 _u32 scalelvl1=0, scalelvl2 = 0;
500 dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
511 int dist_base1 = dist_major;
512 int dist_base2 = dist_major2;
514 if ((!dist_major) && dist_major2) {
515 dist_base1 = dist_major2;
516 scalelvl1 = scalelvl2;
520 dist_q2[0] = (dist_major << 2);
521 if (((
_u32)dist_predict1 == 0xFFFFFE00) || ((
_u32)dist_predict1 == 0x1FF)) {
525 dist_predict1 = (int)(dist_predict1 << scalelvl1);
526 dist_q2[1] = (dist_predict1 + dist_base1) << 2;
530 if (((
_u32)dist_predict2 == 0xFFFFFE00) || ((
_u32)dist_predict2 == 0x1FF)) {
534 dist_predict2 = (int)(dist_predict2 << scalelvl2);
535 dist_q2[2] = (dist_predict2 + dist_base2) << 2;
538 for (
int cpos = 0; cpos < 3; ++cpos)
541 syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
547 int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
549 if (dist_q2[cpos] >= (50 * 4))
551 const int k1 = 98361;
552 const int k2 = int(k1 / dist_q2[cpos]);
554 offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
557 angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
558 currentAngle_raw_q16 += angleInc_q16;
560 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
561 if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
564 hqNode.
flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
591 const _u64 channelBaudRate = timing.native_baudrate ? timing.native_baudrate : 256000;
597 tranmissionDelay = 100;
601 const _u64 sampleDelay = (timing.sample_duration_uS >> 1);
602 const _u64 sampleFilterDelay = timing.sample_duration_uS;
603 const _u64 groupingDelay = (39 - sampleIdx) * timing.sample_duration_uS;
606 return sampleFilterDelay + sampleDelay + tranmissionDelay + timing.linkage_delay_uS + groupingDelay;
610 : _cached_scan_node_buf_pos(0)
611 , _is_previous_capsuledataRdy(false)
612 , _cached_last_data_timestamp_us(0)
642 for (
size_t pos = 0; pos < cnt; ++pos) {
647 _u8 tmp = (current_data >> 4);
660 _u8 tmp = (current_data >> 4);
681 _u8 recvChecksum = ((node->s_checksum_1 & 0xF) | (node->s_checksum_2 << 4));
688 if (recvChecksum == checksum)
693 #ifdef _CPU_ENDIAN_BIG
694 node->start_angle_sync_q6 =
le16_to_cpu(node->start_angle_sync_q6);
695 for (
size_t cpos = 0; cpos <
_countof(node->cabins); ++cpos) {
696 node->cabins[cpos].distance_angle_1 =
le16_to_cpu(node->cabins[cpos].distance_angle_1);
697 node->cabins[cpos].distance_angle_2 =
le16_to_cpu(node->cabins[cpos].distance_angle_2);
738 static int lastNodeSyncBit = 0;
743 int currentStartAngle_q8 = ((dense_capsule.start_angle_sync_q6 & 0x7FFF) << 2);
746 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
747 if (prevStartAngle_q8 > currentStartAngle_q8) {
748 diffAngle_q8 += (360 << 8);
750 int maxDiffAngleThreshold_q8 = (360 * 100 *
_countof(dense_capsule.cabins) / (1000000 /
_cachedTimingDesc.sample_duration_uS)) << 8;
751 if (diffAngle_q8 > maxDiffAngleThreshold_q8) {
756 int angleInc_q16 = (diffAngle_q8 << 8) / 40;
757 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
765 angle_q6 = (currentAngle_raw_q16 >> 10);
766 syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < (angleInc_q16 << 1)) ? 1 : 0;
767 syncBit = (syncBit ^ lastNodeSyncBit) & syncBit;
769 currentAngle_raw_q16 += angleInc_q16;
771 if (angle_q6 < 0) angle_q6 += (360 << 6);
772 if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
777 hqNode.
flag = (syncBit | ((!syncBit) << 1));
783 lastNodeSyncBit = syncBit;
801 const _u64 channelBaudRate = timing.native_baudrate ? timing.native_baudrate : 1000000;
803 _u64 tranmissionDelay = 1000000ULL *
sizeof(sl_lidar_response_ultra_dense_capsule_measurement_nodes_t) * 10 / channelBaudRate;
807 tranmissionDelay = 100;
811 const _u64 sampleDelay = (timing.sample_duration_uS >> 1);
812 const _u64 sampleFilterDelay = timing.sample_duration_uS;
813 const _u64 groupingDelay = ((32 * 2 - 1) - sampleIdx) * timing.sample_duration_uS;
816 return sampleFilterDelay + sampleDelay + tranmissionDelay + timing.linkage_delay_uS + groupingDelay;
821 : _cached_scan_node_buf_pos(0)
822 , _is_previous_capsuledataRdy(false)
823 , _cached_last_data_timestamp_us(0)
824 , _last_node_sync_bit(0)
854 for (
size_t pos = 0; pos < cnt; ++pos) {
859 _u8 tmp = (current_data >> 4);
872 _u8 tmp = (current_data >> 4);
893 _u8 recvChecksum = ((node->s_checksum_1 & 0xF) | (node->s_checksum_2 << 4));
900 if (recvChecksum == checksum)
905 #ifdef _CPU_ENDIAN_BIG
906 node->start_angle_sync_q6 =
le16_to_cpu(node->start_angle_sync_q6);
907 for (
size_t cpos = 0; cpos <
_countof(node->cabins); ++cpos) {
908 node->cabins[cpos].qualityl_distance_scale[0] =
le16_to_cpu(node->cabins[cpos].qualityl_distance_scale[0]);
909 node->cabins[cpos].qualityl_distance_scale[1] =
le16_to_cpu(node->cabins[cpos].qualityl_distance_scale[1]);
958 int currentStartAngle_q8 = ((ultra_dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
963 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
964 if (prevStartAngle_q8 > currentStartAngle_q8) {
965 diffAngle_q8 += (360 << 8);
968 int maxDiffAngleThreshold_q8 = (360 * 100 *
_countof(ultra_dense_capsule->cabins) / (1000000 /
_cachedTimingDesc.sample_duration_uS)) << 8;
969 if (diffAngle_q8 > maxDiffAngleThreshold_q8) {
973 #define DISTANCE_THRESHOLD_TO_SCALE_1 2046 // (2^10 - 1)*2 mm
974 #define DISTANCE_THRESHOLD_TO_SCALE_2 8187 // (2^11 - 1)*3 + 2046 mm
975 #define DISTANCE_THRESHOLD_TO_SCALE_3 24567 // (2^12 - 1)*4 + 8187 mm
976 int angleInc_q16 = (diffAngle_q8 << 8) / 64;
977 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
982 size_t cabin_idx = pos >> 1;
983 _u32 quality_dist_scale;
991 _u8 scale = quality_dist_scale & 0x3;
997 quality = quality_dist_scale >> 12;
998 dist_q2 = (quality_dist_scale & 0xFFC) * 2;
1006 quality = (quality_dist_scale >> 13) << 1;
1010 quality = (quality_dist_scale >> 14) << 2;
1014 quality = (quality_dist_scale >> 15) << 3;
1019 angle_q6 = (currentAngle_raw_q16 >> 10);
1020 syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < (angleInc_q16 << 1)) ? 1 : 0;
1023 currentAngle_raw_q16 += angleInc_q16;
1025 if (angle_q6 < 0) angle_q6 += (360 << 6);
1026 if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
1033 hqNode.
flag = (syncBit | ((!syncBit) << 1));