51 #define min(a,b) (((a) < (b)) ? (a) : (b)) 54 namespace rp {
namespace standalone{
namespace rplidar {
56 #define DEPRECATED_WARN(fn, replacement) do { \ 57 static bool __shown__ = false; \ 59 printDeprecationWarn(fn, replacement); \ 66 fprintf(stderr,
"*WARN* YOU ARE USING DEPRECATED API: %s, PLEASE MOVE TO %s\n", fn, replacement);
105 : _isConnected(false)
107 , _isSupportingMotorCtrl(false)
149 _u8 recvBuffer[
sizeof(rplidar_ans_header_t)];
150 _u8 *headerBuffer =
reinterpret_cast<_u8 *
>(header);
153 while ((waitTime=
getms() - startTs) <= timeout) {
154 size_t remainSize =
sizeof(rplidar_ans_header_t) - recvPos;
160 if(recvSize > remainSize) recvSize = remainSize;
164 for (
size_t pos = 0; pos < recvSize; ++pos) {
165 _u8 currentByte = recvBuffer[pos];
180 headerBuffer[recvPos++] = currentByte;
182 if (recvPos ==
sizeof(rplidar_ans_header_t)) {
208 rplidar_ans_header_t response_header;
219 if ( header_size <
sizeof(rplidar_response_device_health_t)) {
226 _chanDev->
recvdata(reinterpret_cast<_u8 *>(&healthinfo),
sizeof(healthinfo));
248 rplidar_ans_header_t response_header;
259 if (header_size <
sizeof(rplidar_response_device_info_t)) {
273 DEPRECATED_WARN(
"getFrequency(bool,size_t,float&,bool&)",
"getFrequency(const RplidarScanMode&,size_t,float&)");
276 frequency = 1000000.0f/(count * sample_duration);
278 if (sample_duration <= 277) {
290 frequency = 1000000.0f / (count * sample_duration);
298 _u8 recvBuffer[
sizeof(rplidar_response_measurement_node_t)];
299 _u8 *nodeBuffer = (
_u8*)node;
302 while ((waitTime=
getms() - startTs) <= timeout) {
303 size_t remainSize =
sizeof(rplidar_response_measurement_node_t) - recvPos;
309 if (recvSize > remainSize) recvSize = remainSize;
313 for (
size_t pos = 0; pos < recvSize; ++pos) {
314 _u8 currentByte = recvBuffer[pos];
318 _u8 tmp = (currentByte>>1);
319 if ( (tmp ^ currentByte) & 0x1 ) {
338 nodeBuffer[recvPos++] = currentByte;
340 if (recvPos ==
sizeof(rplidar_response_measurement_node_t)) {
356 size_t recvNodeCount = 0;
361 while ((waitTime =
getms() - startTs) <= timeout && recvNodeCount < count) {
362 rplidar_response_measurement_node_t node;
367 nodebuffer[recvNodeCount++] = node;
369 if (recvNodeCount == count)
return RESULT_OK;
371 count = recvNodeCount;
380 _u8 recvBuffer[
sizeof(rplidar_response_capsule_measurement_nodes_t)];
381 _u8 *nodeBuffer = (
_u8*)&node;
385 while ((waitTime=
getms() - startTs) <= timeout) {
386 size_t remainSize =
sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
394 if (recvSize > remainSize) recvSize = remainSize;
398 for (
size_t pos = 0; pos < recvSize; ++pos) {
399 _u8 currentByte = recvBuffer[pos];
404 _u8 tmp = (currentByte>>4);
416 _u8 tmp = (currentByte>>4);
427 nodeBuffer[recvPos++] = currentByte;
428 if (recvPos ==
sizeof(rplidar_response_capsule_measurement_nodes_t)) {
431 _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2<<4));
433 cpos <
sizeof(rplidar_response_capsule_measurement_nodes_t); ++cpos)
435 checksum ^= nodeBuffer[cpos];
437 if (recvChecksum == checksum)
465 _u8 recvBuffer[
sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)];
466 _u8 *nodeBuffer = (
_u8*)&node;
469 while ((waitTime=
getms() - startTs) <= timeout) {
470 size_t remainSize =
sizeof(rplidar_response_ultra_capsule_measurement_nodes_t) - recvPos;
478 if (recvSize > remainSize) recvSize = remainSize;
482 for (
size_t pos = 0; pos < recvSize; ++pos) {
483 _u8 currentByte = recvBuffer[pos];
487 _u8 tmp = (currentByte>>4);
499 _u8 tmp = (currentByte>>4);
511 nodeBuffer[recvPos++] = currentByte;
512 if (recvPos ==
sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
515 _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
518 cpos <
sizeof(rplidar_response_ultra_capsule_measurement_nodes_t); ++cpos)
520 checksum ^= nodeBuffer[cpos];
523 if (recvChecksum == checksum)
545 rplidar_response_measurement_node_t local_buf[128];
548 size_t scan_count = 0;
550 memset(local_scan, 0,
sizeof(local_scan));
563 for (
size_t pos = 0; pos < count; ++pos)
569 if ((local_scan[0].
flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
580 convert(local_buf[pos], nodeHq);
581 local_scan[scan_count++] = nodeHq;
582 if (scan_count ==
_countof(local_scan)) scan_count-=1;
612 rplidar_ans_header_t response_header;
623 if (header_size <
sizeof(rplidar_response_measurement_node_t)) {
638 DEPRECATED_WARN(
"checkExpressScanSupported(bool&,_u32)",
"getAllSupportedScanModes()");
640 rplidar_response_device_info_t devinfo;
647 if (devinfo.firmware_version >= ((0x1<<8) | 17)) {
649 rplidar_response_sample_rate_t sample_rate;
660 rplidar_response_capsule_measurement_nodes_t capsule_node;
664 size_t scan_count = 0;
666 memset(local_scan, 0,
sizeof(local_scan));
695 for (
size_t pos = 0; pos < count; ++pos)
701 if ((local_scan[0].
flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
710 local_scan[scan_count++] = local_buf[pos];
711 if (scan_count ==
_countof(local_scan)) scan_count-=1;
728 rplidar_response_ultra_capsule_measurement_nodes_t ultra_capsule_node;
732 size_t scan_count = 0;
734 memset(local_scan, 0,
sizeof(local_scan));
752 for (
size_t pos = 0; pos < count; ++pos)
758 if ((local_scan[0].
flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
767 local_scan[scan_count++] = local_buf[pos];
768 if (scan_count ==
_countof(local_scan)) scan_count-=1;
789 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF)<< 2);
792 diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
793 if (prevStartAngle_q8 > currentStartAngle_q8) {
794 diffAngle_q8 += (360<<8);
797 int angleInc_q16 = (diffAngle_q8 << 3);
798 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
811 angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3<<13))>>10);
812 syncBit[0] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
813 currentAngle_raw_q16 += angleInc_q16;
816 angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3<<13))>>10);
817 syncBit[1] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
818 currentAngle_raw_q16 += angleInc_q16;
820 for (
int cpos = 0; cpos < 2; ++cpos) {
822 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360<<6);
823 if (angle_q6[cpos] >= (360<<6)) angle_q6[cpos] -= (360<<6);
828 node.
flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
832 nodebuffer[nodeCount++] = node;
844 const rplidar_response_dense_capsule_measurement_nodes_t *dense_capsule =
reinterpret_cast<const rplidar_response_dense_capsule_measurement_nodes_t*
>(&capsule);
848 int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
851 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
852 if (prevStartAngle_q8 > currentStartAngle_q8) {
853 diffAngle_q8 += (360 << 8);
856 int angleInc_q16 = (diffAngle_q8 << 8)/40;
857 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
865 angle_q6 = (currentAngle_raw_q16 >> 10);
866 syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
867 currentAngle_raw_q16 += angleInc_q16;
869 if (angle_q6 < 0) angle_q6 += (360 << 6);
870 if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
877 node.
flag = (syncBit | ((!syncBit) << 1));
881 nodebuffer[nodeCount++] = node;
893 rplidar_response_hq_capsule_measurement_nodes_t hq_node;
897 size_t scan_count = 0;
899 memset(local_scan, 0,
sizeof(local_scan));
914 for (
size_t pos = 0; pos < count; ++pos)
919 if ((local_scan[0].
flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
928 local_scan[scan_count++] = local_buf[pos];
929 if (scan_count ==
_countof(local_scan)) scan_count -= 1;
951 for (i = 0; i<bw; i++){
954 var |= 1 << (bw - 1 - i);
969 for (i = 0; i<256; i++){
971 for (j = 0; j<8; j++){
986 pch = (
unsigned char*)input;
987 _u8 leftBytes = 4 - len & 0x3;
989 for (i = 0; i<len; i++){
990 index = (
unsigned char)(crc^*pch);
991 crc = (crc >> 8) ^ table[index];
995 for (i = 0; i < leftBytes; i++) {
996 index = (
unsigned char)(crc^0);
997 crc = (crc >> 8) ^ table[index];
999 return crc^0xffffffff;
1021 _u8 recvBuffer[
sizeof(rplidar_response_hq_capsule_measurement_nodes_t)];
1022 _u8 *nodeBuffer = (
_u8*)&node;
1025 while ((waitTime=
getms() - startTs) <= timeout) {
1026 size_t remainSize =
sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - recvPos;
1034 if (recvSize > remainSize) recvSize = remainSize;
1038 for (
size_t pos = 0; pos < recvSize; ++pos) {
1039 _u8 currentByte = recvBuffer[pos];
1043 _u8 tmp = (currentByte);
1054 case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1 - 4:
1059 case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1:
1065 nodeBuffer[recvPos++] = currentByte;
1066 if (recvPos ==
sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1067 _u32 crcCalc2 =
_crc32(nodeBuffer,
sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 4);
1069 if(crcCalc2 == node.crc32){
1091 nodebuffer[nodeCount++] = node_hq.node_hq[pos];
1102 static const _u32 VBS_SCALED_BASE[] = {
1110 static const _u32 VBS_SCALED_LVL[] = {
1118 static const _u32 VBS_TARGET_BASE[] = {
1126 for (
size_t i = 0; i <
_countof(VBS_SCALED_BASE); ++i)
1128 int remain = ((int)scaled - (
int)VBS_SCALED_BASE[i]);
1130 scaleLevel = VBS_SCALED_LVL[i];
1131 return VBS_TARGET_BASE[i] + (remain << scaleLevel);
1142 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
1145 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1146 if (prevStartAngle_q8 > currentStartAngle_q8) {
1147 diffAngle_q8 += (360 << 8);
1150 int angleInc_q16 = (diffAngle_q8 << 3) / 3;
1151 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1162 int dist_major = (combined_x3 & 0xFFF);
1167 int dist_predict1 = (((int)(combined_x3 << 10)) >> 22);
1168 int dist_predict2 = (((int)combined_x3) >> 22);
1172 _u32 scalelvl1, scalelvl2;
1177 dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
1188 int dist_base1 = dist_major;
1189 int dist_base2 = dist_major2;
1191 if ((!dist_major) && dist_major2) {
1192 dist_base1 = dist_major2;
1193 scalelvl1 = scalelvl2;
1197 dist_q2[0] = (dist_major << 2);
1198 if ((dist_predict1 == 0xFFFFFE00) || (dist_predict1 == 0x1FF)) {
1201 dist_predict1 = (dist_predict1 << scalelvl1);
1202 dist_q2[1] = (dist_predict1 + dist_base1) << 2;
1206 if ((dist_predict2 == 0xFFFFFE00) || (dist_predict2 == 0x1FF)) {
1209 dist_predict2 = (dist_predict2 << scalelvl2);
1210 dist_q2[2] = (dist_predict2 + dist_base2) << 2;
1214 for (
int cpos = 0; cpos < 3; ++cpos)
1217 syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1219 int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
1221 if (dist_q2[cpos] >= (50 * 4))
1223 const int k1 = 98361;
1224 const int k2 = int(k1 / dist_q2[cpos]);
1226 offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
1229 angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
1230 currentAngle_raw_q16 += angleInc_q16;
1232 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
1233 if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
1237 node.
flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
1242 nodebuffer[nodeCount++] = node;
1256 rplidar_response_device_info_t devinfo;
1261 if (devinfo.firmware_version >= ((0x1 << 8) | 24)) {
1269 rplidar_payload_get_scan_conf_t query;
1270 memset(&query, 0,
sizeof(query));
1272 int sizeVec = reserve.size();
1274 int maxLen =
sizeof(query.reserved) /
sizeof(query.reserved[0]);
1275 if (sizeVec > maxLen) sizeVec = maxLen;
1278 memcpy(query.reserved, &reserve[0], reserve.size());
1288 rplidar_ans_header_t response_header;
1299 if (header_size <
sizeof(type)) {
1307 std::vector<_u8> dataBuf;
1308 dataBuf.resize(header_size);
1312 _u32 replyType = -1;
1313 memcpy(&replyType, &dataBuf[0],
sizeof(type));
1314 if (replyType != type) {
1319 int payLoadLen = header_size -
sizeof(
type);
1322 if (payLoadLen <= 0) {
1326 outputBuf.resize(payLoadLen);
1327 memcpy(&outputBuf[0], &dataBuf[0] +
sizeof(type), payLoadLen);
1335 std::vector<_u8> answer;
1336 bool lidarSupportConfigCmds =
false;
1340 if (lidarSupportConfigCmds)
1346 if (answer.size() <
sizeof(
_u16)) {
1350 const _u16 *p_answer =
reinterpret_cast<const _u16*
>(&answer[0]);
1351 outMode = *p_answer;
1366 std::vector<_u8> reserve(2);
1367 memcpy(&reserve[0], &scanModeID,
sizeof(scanModeID));
1369 std::vector<_u8> answer;
1375 if (answer.size() <
sizeof(
_u32))
1380 sampleDurationRes = (float)(*result >> 8);
1387 std::vector<_u8> reserve(2);
1388 memcpy(&reserve[0], &scanModeID,
sizeof(scanModeID));
1390 std::vector<_u8> answer;
1396 if (answer.size() <
sizeof(
_u32))
1401 maxDistance = (float)(*result >> 8);
1408 std::vector<_u8> reserve(2);
1409 memcpy(&reserve[0], &scanModeID,
sizeof(scanModeID));
1411 std::vector<_u8> answer;
1417 if (answer.size() <
sizeof(
_u8))
1421 const _u8 *
result =
reinterpret_cast<const _u8*
>(&answer[0]);
1429 std::vector<_u8> reserve(2);
1430 memcpy(&reserve[0], &scanModeID,
sizeof(scanModeID));
1432 std::vector<_u8> answer;
1438 int len = answer.size();
1440 memcpy(modeName, &answer[0], len);
1447 bool confProtocolSupported =
false;
1451 if (confProtocolSupported)
1461 for (
_u16 i = 0; i < modeCount; i++)
1464 memset(&scanModeInfoTmp, 0,
sizeof(scanModeInfoTmp));
1465 scanModeInfoTmp.
id = i;
1486 outModes.push_back(scanModeInfoTmp);
1492 rplidar_response_sample_rate_t sampleRateTmp;
1496 bool ifSupportExpScan =
false;
1502 stdScanModeInfo.
us_per_sample = sampleRateTmp.std_sample_duration_us;
1505 strcpy(stdScanModeInfo.
scan_mode,
"Standard");
1506 outModes.push_back(stdScanModeInfo);
1507 if (ifSupportExpScan)
1511 expScanModeInfo.
us_per_sample = sampleRateTmp.express_sample_duration_us;
1514 strcpy(expScanModeInfo.
scan_mode,
"Express");
1515 outModes.push_back(expScanModeInfo);
1525 std::vector<_u8> answer;
1531 if (answer.size() <
sizeof(
_u16)) {
1534 const _u16 *p_answer =
reinterpret_cast<const _u16*
>(&answer[0]);
1535 modeCount = *p_answer;
1545 bool ifSupportLidarConf =
false;
1552 if (ifSupportLidarConf)
1564 bool isExpScanSupported =
false;
1569 if (isExpScanSupported)
1577 if(ifSupportLidarConf)
1611 rplidar_response_sample_rate_t sampleRateTmp;
1614 outUsedScanMode->
us_per_sample = sampleRateTmp.std_sample_duration_us;
1617 strcpy(outUsedScanMode->
scan_mode,
"Standard");
1634 return startScan(force,
false, 0, outUsedScanMode);
1638 bool ifSupportLidarConf =
false;
1642 if (outUsedScanMode)
1644 outUsedScanMode->
id = scanMode;
1645 if (ifSupportLidarConf)
1675 rplidar_response_sample_rate_t sampleRateTmp;
1679 outUsedScanMode->
us_per_sample = sampleRateTmp.express_sample_duration_us;
1682 strcpy(outUsedScanMode->
scan_mode,
"Express");
1688 if (ifSupportLidarConf)
1700 rplidar_payload_express_scan_t scanReq;
1701 memset(&scanReq, 0,
sizeof(scanReq));
1703 scanReq.working_mode =
_u8(scanMode);
1704 scanReq.working_flags = options;
1711 rplidar_ans_header_t response_header;
1717 if (response_header.type != scanAnsType) {
1725 if (header_size <
sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1734 if (header_size <
sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1742 if (header_size <
sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1750 if (header_size <
sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
1797 for (
size_t i = 0; i < size_to_copy; i++)
1800 count = size_to_copy;
1827 count = size_to_copy;
1840 DEPRECATED_WARN(
"getScanDataWithInterval(rplidar_response_measurement_node_t*, size_t&)",
"getScanDataWithInterval(rplidar_response_measurement_node_hq_t*, size_t&)");
1842 size_t size_to_copy = 0;
1851 for (
size_t i = 0; i < size_to_copy; i++)
1857 count = size_to_copy;
1864 size_t size_to_copy = 0;
1876 count = size_to_copy;
1881 static inline float getAngle(
const rplidar_response_measurement_node_t& node)
1886 static inline void setAngle(rplidar_response_measurement_node_t& node,
float v)
1904 return node.distance_q2;
1912 template <
class TNode>
1918 template <
class TNode >
1921 float inc_origin_angle = 360.f/count;
1925 for (i = 0; i < count; i++) {
1931 float expect_angle =
getAngle(nodebuffer[i+1]) - inc_origin_angle;
1932 if (expect_angle < 0.0
f) expect_angle = 0.0f;
1933 setAngle(nodebuffer[i], expect_angle);
1943 for (i = count - 1; i >= 0; i--) {
1947 while(i != (count - 1)) {
1949 float expect_angle =
getAngle(nodebuffer[i-1]) + inc_origin_angle;
1950 if (expect_angle > 360.0
f) expect_angle -= 360.0f;
1951 setAngle(nodebuffer[i], expect_angle);
1958 float frontAngle =
getAngle(nodebuffer[0]);
1959 for (i = 1; i < count; i++) {
1961 float expect_angle = frontAngle + i * inc_origin_angle;
1962 if (expect_angle > 360.0
f) expect_angle -= 360.0f;
1963 setAngle(nodebuffer[i], expect_angle);
1968 std::sort(nodebuffer, nodebuffer + count, &angleLessThan<TNode>);
1975 DEPRECATED_WARN(
"ascendScanData(rplidar_response_measurement_node_t*, size_t)",
"ascendScanData(rplidar_response_measurement_node_hq_t*, size_t)");
1977 return ascendScanData_<rplidar_response_measurement_node_t>(nodebuffer, count);
1982 return ascendScanData_<rplidar_response_measurement_node_hq_t>(nodebuffer, count);
1988 rplidar_cmd_packet_t *
header =
reinterpret_cast<rplidar_cmd_packet_t *
>(pkt_header);
1993 if (payloadsize && payload) {
1998 header->cmd_flag = cmd;
2006 checksum ^= (payloadsize & 0xFF);
2009 for (
size_t pos = 0; pos < payloadsize; ++pos) {
2010 checksum ^= ((
_u8 *)payload)[pos];
2014 _u8 sizebyte = payloadsize;
2029 DEPRECATED_WARN(
"getSampleDuration_uS",
"RplidarScanMode::us_per_sample");
2035 rplidar_response_device_info_t devinfo;
2042 if (devinfo.firmware_version < ((0x1<<8) | 17)) {
2056 rplidar_ans_header_t response_header;
2067 if ( header_size <
sizeof(rplidar_response_sample_rate_t)) {
2091 rplidar_payload_acc_board_flag_t
flag;
2098 rplidar_ans_header_t response_header;
2109 if ( header_size <
sizeof(rplidar_response_acc_board_flag_t)) {
2116 rplidar_response_acc_board_flag_t acc_board_flag;
2117 _chanDev->
recvdata(reinterpret_cast<_u8 *>(&acc_board_flag),
sizeof(acc_board_flag));
2129 rplidar_payload_motor_pwm_t motor_pwm;
2130 motor_pwm.pwm_value = pwm;
#define offsetof(_structure, _field)
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT
virtual u_result connect(const char *ipStr, _u32 port, _u32 flag=0)
#define CLASS_THREAD(c, x)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT
static bool angleLessThan(const TNode &a, const TNode &b)
#define RPLIDAR_ANS_TYPE_MEASUREMENT_HQ
#define RPLIDAR_CMD_FORCE_SCAN
#define RPLIDAR_CONF_SCAN_COMMAND_EXPRESS
rplidar_response_measurement_node_hq_t node_hq[16]
rp::hal::Thread _cachethread
#define RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE
#define RPLIDAR_CMD_GET_LIDAR_CONF
virtual void _capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
#define RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED
rplidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
virtual u_result checkSupportConfigCommands(bool &outSupport, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RPLIDAR_ANS_TYPE_GET_LIDAR_CONF
bool _is_previous_capsuledataRdy
virtual u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_VARBITSCALE_X4_DEST_VAL
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_ANS_TYPE_SAMPLE_RATE
virtual u_result startScanNormal(bool force, _u32 timeout=DEFAULT_TIMEOUT)
bool _isSupportingMotorCtrl
size_t _cached_scan_node_hq_count_for_interval_retrieve
virtual u_result _waitResponseHeader(rplidar_ans_header_t *header, _u32 timeout=DEFAULT_TIMEOUT)
virtual void _dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
bool _is_previous_HqdataRdy
virtual u_result grabScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
virtual u_result reset(_u32 timeout=DEFAULT_TIMEOUT)
virtual u_result _cacheCapsuledScanData()
static void DisposeDriver(RPlidarDriver *drv)
#define RPLIDAR_VARBITSCALE_X8_SRC_BIT
virtual void _ultraCapsuleToNormal(const rplidar_response_ultra_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
virtual u_result _waitUltraCapsuledNode(rplidar_response_ultra_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_VARBITSCALE_X2_SRC_BIT
virtual u_result startScan(bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)
static void printDeprecationWarn(const char *fn, const char *replacement)
rplidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)
virtual void disconnect()=0
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_ANS_HEADER_SIZE_MASK
virtual u_result connect(const char *port_path, _u32 baudrate, _u32 flag=0)
_u16 _cached_sampleduration_std
#define RPLIDAR_CMD_GET_DEVICE_INFO
#define RPLIDAR_ANS_TYPE_DEVHEALTH
#define RPLIDAR_CMD_SYNC_BYTE
virtual u_result clearNetSerialRxCache()
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT
virtual u_result getLidarConf(_u32 type, std::vector< _u8 > &outputBuf, const std::vector< _u8 > &reserve=std::vector< _u8 >(), _u32 timeout=DEFAULT_TIMEOUT)
virtual bool waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=NULL)=0
virtual u_result grabScanDataHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
virtual bool bind(const char *, uint32_t)=0
virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT)
static _u32 _varbitscale_decode(_u32 scaled, _u32 &scaleLevel)
#define RPLIDAR_VARBITSCALE_X16_SRC_BIT
#define RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE
static void _crc32_init(_u32 poly)
#define RESULT_INSUFFICIENT_MEMORY
#define RPLIDAR_ANS_SYNC_BYTE1
virtual u_result _cacheHqScanData()
virtual u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
virtual u_result _sendCommand(_u8 cmd, const void *payload=NULL, size_t payloadsize=0)
#define RPLIDAR_RESP_MEASUREMENT_HQ_SYNC
#define RPLIDAR_CMD_GET_SAMPLERATE
virtual u_result getHealth(rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)
virtual int senddata(const _u8 *data, size_t size)=0
virtual void ReleaseRxTx()
_u16 _cached_sampleduration_express
virtual ~RPlidarDriverSerial()
virtual u_result getScanModeName(char *modeName, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
virtual u_result startMotor()
Start RPLIDAR's motor when using accessory board.
#define RPLIDAR_CMD_RESET
virtual u_result setMotorPWM(_u16 pwm)
virtual u_result _cacheUltraCapsuledScanData()
#define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK
static _u32 _crc32cal(_u32 crc, void *input, _u16 len)
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMDFLAG_HAS_PAYLOAD
rplidar_response_measurement_node_hq_t _cached_scan_node_hq_buf[8192]
#define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG
virtual u_result getTypicalScanMode(_u16 &outMode, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get typical scan mode of lidar.
virtual u_result getFrequency(bool inExpressMode, size_t count, float &frequency, bool &is4kmode)
virtual u_result _waitNode(rplidar_response_measurement_node_t *node, _u32 timeout=DEFAULT_TIMEOUT)
size_t _cached_scan_node_hq_count
static u_result ascendScanData_(TNode *nodebuffer, size_t count)
#define RPLIDAR_CMD_SET_MOTOR_PWM
static void setAngle(rplidar_response_measurement_node_t &node, float v)
#define RPLIDAR_CMD_EXPRESS_SCAN
void set(bool isSignal=true)
#define RPLIDAR_CONF_SCAN_MODE_ANS_TYPE
RPlidarDriverImplCommon()
#define RESULT_OPERATION_TIMEOUT
#define RPLIDAR_ANS_TYPE_MEASUREMENT
u_result join(unsigned long timeout=-1)
#define RPLIDAR_CMD_GET_ACC_BOARD_FLAG
#define RPLIDAR_CONF_SCAN_COMMAND_STD
void _disableDataGrabbing()
virtual bool isConnected()
Returns TRUE when the connection has been established.
virtual u_result ascendScanData(rplidar_response_measurement_node_t *nodebuffer, size_t count)
static void convert(const rplidar_response_measurement_node_t &from, rplidar_response_measurement_node_hq_t &to)
rplidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata
virtual u_result getDeviceInfo(rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT
Locker::LOCK_STATUS lock(unsigned long timeout=0xFFFFFFFF)
virtual u_result getScanModeCount(_u16 &modeCount, _u32 timeoutInMs=DEFAULT_TIMEOUT)
static _u32 _bitrev(_u32 input, _u16 bw)
virtual void _HqToNormal(const rplidar_response_hq_capsule_measurement_nodes_t &node_hq, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
unsigned long wait(unsigned long timeout=0xFFFFFFFF)
#define RPLIDAR_CONF_SCAN_MODE_NAME
#define RPLIDAR_CONF_SCAN_MODE_COUNT
static float getAngle(const rplidar_response_measurement_node_t &node)
virtual u_result getAllSupportedScanModes(std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get all scan modes that supported by lidar.
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1
#define DEFAULT_MOTOR_PWM
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
virtual u_result getScanDataWithInterval(rplidar_response_measurement_node_t *nodebuffer, size_t &count)
#define RPLIDAR_VARBITSCALE_X8_DEST_VAL
#define RPLIDAR_CONF_SCAN_MODE_TYPICAL
virtual u_result checkExpressScanSupported(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
virtual u_result _waitHqNode(rplidar_response_hq_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RESULT_OPERATION_FAIL
#define RPLIDAR_VARBITSCALE_X2_DEST_VAL
virtual u_result getScanModeAnsType(_u8 &ansType, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
virtual u_result stopMotor()
Stop RPLIDAR's motor when using accessory board.
#define RESULT_ALREADY_DONE
virtual u_result getLidarSampleDuration(float &sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2
#define RPLIDAR_CMD_GET_DEVICE_HEALTH
#define RPLIDAR_VARBITSCALE_X16_DEST_VAL
#define DEPRECATED_WARN(fn, replacement)
rplidar_response_measurement_node_hq_t _cached_scan_node_hq_buf_for_interval_retrieve[8192]
#define RPLIDAR_ANS_SYNC_BYTE2
static u_result _crc32(_u8 *ptr, _u32 len)
static _u16 getDistanceQ2(const rplidar_response_measurement_node_t &node)
rplidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata
virtual u_result getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
virtual u_result _cacheScanData()
#define RESULT_INVALID_DATA
virtual u_result _waitScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_ANS_TYPE_DEVINFO
virtual u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
virtual ~RPlidarDriverTCP()
virtual int recvdata(unsigned char *data, size_t size)=0
#define RPLIDAR_VARBITSCALE_X4_SRC_BIT