00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "sdkcommon.h"
00036
00037 #include "hal/abs_rxtx.h"
00038 #include "hal/thread.h"
00039 #include "hal/types.h"
00040 #include "hal/assert.h"
00041 #include "hal/locker.h"
00042 #include "hal/socket.h"
00043 #include "hal/event.h"
00044 #include "rplidar_driver_impl.h"
00045 #include "rplidar_driver_serial.h"
00046 #include "rplidar_driver_TCP.h"
00047
00048 #include <algorithm>
00049
00050 #ifndef min
00051 #define min(a,b) (((a) < (b)) ? (a) : (b))
00052 #endif
00053
00054 namespace rp { namespace standalone{ namespace rplidar {
00055
00056 #define DEPRECATED_WARN(fn, replacement) do { \
00057 static bool __shown__ = false; \
00058 if (!__shown__) { \
00059 printDeprecationWarn(fn, replacement); \
00060 __shown__ = true; \
00061 } \
00062 } while (0)
00063
00064 static void printDeprecationWarn(const char* fn, const char* replacement)
00065 {
00066 fprintf(stderr, "*WARN* YOU ARE USING DEPRECATED API: %s, PLEASE MOVE TO %s\n", fn, replacement);
00067 }
00068
00069 static void convert(const rplidar_response_measurement_node_t& from, rplidar_response_measurement_node_hq_t& to)
00070 {
00071 to.angle_z_q14 = (((from.angle_q6_checkbit) >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) << 8) / 90;
00072 to.dist_mm_q2 = from.distance_q2;
00073 to.flag = (from.sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT);
00074 to.quality = (from.sync_quality >> RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT;
00075 }
00076
00077 static void convert(const rplidar_response_measurement_node_hq_t& from, rplidar_response_measurement_node_t& to)
00078 {
00079 to.sync_quality = (from.flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT) | ((from.quality >> RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT);
00080 to.angle_q6_checkbit = 1 | (((from.angle_z_q14 * 90) >> 8) << RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT);
00081 to.distance_q2 = from.dist_mm_q2 > _u16(-1) ? _u16(0) : _u16(from.dist_mm_q2);
00082 }
00083
00084
00085 RPlidarDriver * RPlidarDriver::CreateDriver(_u32 drivertype)
00086 {
00087 switch (drivertype) {
00088 case DRIVER_TYPE_SERIALPORT:
00089 return new RPlidarDriverSerial();
00090 case DRIVER_TYPE_TCP:
00091 return new RPlidarDriverTCP();
00092 default:
00093 return NULL;
00094 }
00095 }
00096
00097
00098 void RPlidarDriver::DisposeDriver(RPlidarDriver * drv)
00099 {
00100 delete drv;
00101 }
00102
00103
00104 RPlidarDriverImplCommon::RPlidarDriverImplCommon()
00105 : _isConnected(false)
00106 , _isScanning(false)
00107 , _isSupportingMotorCtrl(false)
00108 {
00109 _cached_scan_node_hq_count = 0;
00110 _cached_scan_node_hq_count_for_interval_retrieve = 0;
00111 _cached_sampleduration_std = LEGACY_SAMPLE_DURATION;
00112 _cached_sampleduration_express = LEGACY_SAMPLE_DURATION;
00113 }
00114
00115 bool RPlidarDriverImplCommon::isConnected()
00116 {
00117 return _isConnected;
00118 }
00119
00120
00121 u_result RPlidarDriverImplCommon::reset(_u32 timeout)
00122 {
00123 u_result ans;
00124
00125 {
00126 rp::hal::AutoLocker l(_lock);
00127
00128 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_RESET))) {
00129 return ans;
00130 }
00131 }
00132 return RESULT_OK;
00133 }
00134
00135
00136 u_result RPlidarDriverImplCommon::clearNetSerialRxCache()
00137 {
00138 if (!isConnected()) return RESULT_OPERATION_FAIL;
00139
00140 _chanDev->flush();
00141
00142 return RESULT_OK;
00143 }
00144
00145 u_result RPlidarDriverImplCommon::_waitResponseHeader(rplidar_ans_header_t * header, _u32 timeout)
00146 {
00147 int recvPos = 0;
00148 _u32 startTs = getms();
00149 _u8 recvBuffer[sizeof(rplidar_ans_header_t)];
00150 _u8 *headerBuffer = reinterpret_cast<_u8 *>(header);
00151 _u32 waitTime;
00152
00153 while ((waitTime=getms() - startTs) <= timeout) {
00154 size_t remainSize = sizeof(rplidar_ans_header_t) - recvPos;
00155 size_t recvSize;
00156
00157 bool ans = _chanDev->waitfordata(remainSize, timeout - waitTime, &recvSize);
00158 if(!ans) return RESULT_OPERATION_TIMEOUT;
00159
00160 if(recvSize > remainSize) recvSize = remainSize;
00161
00162 recvSize = _chanDev->recvdata(recvBuffer, recvSize);
00163
00164 for (size_t pos = 0; pos < recvSize; ++pos) {
00165 _u8 currentByte = recvBuffer[pos];
00166 switch (recvPos) {
00167 case 0:
00168 if (currentByte != RPLIDAR_ANS_SYNC_BYTE1) {
00169 continue;
00170 }
00171
00172 break;
00173 case 1:
00174 if (currentByte != RPLIDAR_ANS_SYNC_BYTE2) {
00175 recvPos = 0;
00176 continue;
00177 }
00178 break;
00179 }
00180 headerBuffer[recvPos++] = currentByte;
00181
00182 if (recvPos == sizeof(rplidar_ans_header_t)) {
00183 return RESULT_OK;
00184 }
00185 }
00186 }
00187
00188 return RESULT_OPERATION_TIMEOUT;
00189 }
00190
00191
00192
00193 u_result RPlidarDriverImplCommon::getHealth(rplidar_response_device_health_t & healthinfo, _u32 timeout)
00194 {
00195 u_result ans;
00196
00197 if (!isConnected()) return RESULT_OPERATION_FAIL;
00198
00199 _disableDataGrabbing();
00200
00201 {
00202 rp::hal::AutoLocker l(_lock);
00203
00204 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_DEVICE_HEALTH))) {
00205 return ans;
00206 }
00207
00208 rplidar_ans_header_t response_header;
00209 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
00210 return ans;
00211 }
00212
00213
00214 if (response_header.type != RPLIDAR_ANS_TYPE_DEVHEALTH) {
00215 return RESULT_INVALID_DATA;
00216 }
00217
00218 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
00219 if ( header_size < sizeof(rplidar_response_device_health_t)) {
00220 return RESULT_INVALID_DATA;
00221 }
00222
00223 if (!_chanDev->waitfordata(header_size, timeout)) {
00224 return RESULT_OPERATION_TIMEOUT;
00225 }
00226 _chanDev->recvdata(reinterpret_cast<_u8 *>(&healthinfo), sizeof(healthinfo));
00227 }
00228 return RESULT_OK;
00229 }
00230
00231
00232
00233 u_result RPlidarDriverImplCommon::getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout)
00234 {
00235 u_result ans;
00236
00237 if (!isConnected()) return RESULT_OPERATION_FAIL;
00238
00239 _disableDataGrabbing();
00240
00241 {
00242 rp::hal::AutoLocker l(_lock);
00243
00244 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_DEVICE_INFO))) {
00245 return ans;
00246 }
00247
00248 rplidar_ans_header_t response_header;
00249 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
00250 return ans;
00251 }
00252
00253
00254 if (response_header.type != RPLIDAR_ANS_TYPE_DEVINFO) {
00255 return RESULT_INVALID_DATA;
00256 }
00257
00258 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
00259 if (header_size < sizeof(rplidar_response_device_info_t)) {
00260 return RESULT_INVALID_DATA;
00261 }
00262
00263 if (!_chanDev->waitfordata(header_size, timeout)) {
00264 return RESULT_OPERATION_TIMEOUT;
00265 }
00266 _chanDev->recvdata(reinterpret_cast<_u8 *>(&info), sizeof(info));
00267 }
00268 return RESULT_OK;
00269 }
00270
00271 u_result RPlidarDriverImplCommon::getFrequency(bool inExpressMode, size_t count, float & frequency, bool & is4kmode)
00272 {
00273 DEPRECATED_WARN("getFrequency(bool,size_t,float&,bool&)", "getFrequency(const RplidarScanMode&,size_t,float&)");
00274
00275 _u16 sample_duration = inExpressMode?_cached_sampleduration_express:_cached_sampleduration_std;
00276 frequency = 1000000.0f/(count * sample_duration);
00277
00278 if (sample_duration <= 277) {
00279 is4kmode = true;
00280 } else {
00281 is4kmode = false;
00282 }
00283
00284 return RESULT_OK;
00285 }
00286
00287 u_result RPlidarDriverImplCommon::getFrequency(const RplidarScanMode& scanMode, size_t count, float & frequency)
00288 {
00289 float sample_duration = scanMode.us_per_sample;
00290 frequency = 1000000.0f / (count * sample_duration);
00291 return RESULT_OK;
00292 }
00293
00294 u_result RPlidarDriverImplCommon::_waitNode(rplidar_response_measurement_node_t * node, _u32 timeout)
00295 {
00296 int recvPos = 0;
00297 _u32 startTs = getms();
00298 _u8 recvBuffer[sizeof(rplidar_response_measurement_node_t)];
00299 _u8 *nodeBuffer = (_u8*)node;
00300 _u32 waitTime;
00301
00302 while ((waitTime=getms() - startTs) <= timeout) {
00303 size_t remainSize = sizeof(rplidar_response_measurement_node_t) - recvPos;
00304 size_t recvSize;
00305
00306 bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
00307 if(!ans) return RESULT_OPERATION_FAIL;
00308
00309 if (recvSize > remainSize) recvSize = remainSize;
00310
00311 recvSize = _chanDev->recvdata(recvBuffer, recvSize);
00312
00313 for (size_t pos = 0; pos < recvSize; ++pos) {
00314 _u8 currentByte = recvBuffer[pos];
00315 switch (recvPos) {
00316 case 0:
00317 {
00318 _u8 tmp = (currentByte>>1);
00319 if ( (tmp ^ currentByte) & 0x1 ) {
00320
00321 } else {
00322 continue;
00323 }
00324
00325 }
00326 break;
00327 case 1:
00328 {
00329 if (currentByte & RPLIDAR_RESP_MEASUREMENT_CHECKBIT) {
00330
00331 } else {
00332 recvPos = 0;
00333 continue;
00334 }
00335 }
00336 break;
00337 }
00338 nodeBuffer[recvPos++] = currentByte;
00339
00340 if (recvPos == sizeof(rplidar_response_measurement_node_t)) {
00341 return RESULT_OK;
00342 }
00343 }
00344 }
00345
00346 return RESULT_OPERATION_TIMEOUT;
00347 }
00348
00349 u_result RPlidarDriverImplCommon::_waitScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
00350 {
00351 if (!_isConnected) {
00352 count = 0;
00353 return RESULT_OPERATION_FAIL;
00354 }
00355
00356 size_t recvNodeCount = 0;
00357 _u32 startTs = getms();
00358 _u32 waitTime;
00359 u_result ans;
00360
00361 while ((waitTime = getms() - startTs) <= timeout && recvNodeCount < count) {
00362 rplidar_response_measurement_node_t node;
00363 if (IS_FAIL(ans = _waitNode(&node, timeout - waitTime))) {
00364 return ans;
00365 }
00366
00367 nodebuffer[recvNodeCount++] = node;
00368
00369 if (recvNodeCount == count) return RESULT_OK;
00370 }
00371 count = recvNodeCount;
00372 return RESULT_OPERATION_TIMEOUT;
00373 }
00374
00375
00376 u_result RPlidarDriverImplCommon::_waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t & node, _u32 timeout)
00377 {
00378 int recvPos = 0;
00379 _u32 startTs = getms();
00380 _u8 recvBuffer[sizeof(rplidar_response_capsule_measurement_nodes_t)];
00381 _u8 *nodeBuffer = (_u8*)&node;
00382 _u32 waitTime;
00383
00384
00385 while ((waitTime=getms() - startTs) <= timeout) {
00386 size_t remainSize = sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
00387 size_t recvSize;
00388
00389 bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
00390 if(!ans)
00391 {
00392 return RESULT_OPERATION_TIMEOUT;
00393 }
00394 if (recvSize > remainSize) recvSize = remainSize;
00395
00396 recvSize = _chanDev->recvdata(recvBuffer, recvSize);
00397
00398 for (size_t pos = 0; pos < recvSize; ++pos) {
00399 _u8 currentByte = recvBuffer[pos];
00400
00401 switch (recvPos) {
00402 case 0:
00403 {
00404 _u8 tmp = (currentByte>>4);
00405 if ( tmp == RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1 ) {
00406
00407 } else {
00408 _is_previous_capsuledataRdy = false;
00409 continue;
00410 }
00411
00412 }
00413 break;
00414 case 1:
00415 {
00416 _u8 tmp = (currentByte>>4);
00417 if (tmp == RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2) {
00418
00419 } else {
00420 recvPos = 0;
00421 _is_previous_capsuledataRdy = false;
00422 continue;
00423 }
00424 }
00425 break;
00426 }
00427 nodeBuffer[recvPos++] = currentByte;
00428 if (recvPos == sizeof(rplidar_response_capsule_measurement_nodes_t)) {
00429
00430 _u8 checksum = 0;
00431 _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2<<4));
00432 for (size_t cpos = offsetof(rplidar_response_capsule_measurement_nodes_t, start_angle_sync_q6);
00433 cpos < sizeof(rplidar_response_capsule_measurement_nodes_t); ++cpos)
00434 {
00435 checksum ^= nodeBuffer[cpos];
00436 }
00437 if (recvChecksum == checksum)
00438 {
00439
00440 if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
00441 {
00442
00443 _is_previous_capsuledataRdy = false;
00444 return RESULT_OK;
00445 }
00446 return RESULT_OK;
00447 }
00448 _is_previous_capsuledataRdy = false;
00449 return RESULT_INVALID_DATA;
00450 }
00451 }
00452 }
00453 _is_previous_capsuledataRdy = false;
00454 return RESULT_OPERATION_TIMEOUT;
00455 }
00456
00457 u_result RPlidarDriverImplCommon::_waitUltraCapsuledNode(rplidar_response_ultra_capsule_measurement_nodes_t & node, _u32 timeout)
00458 {
00459 if (!_isConnected) {
00460 return RESULT_OPERATION_FAIL;
00461 }
00462
00463 int recvPos = 0;
00464 _u32 startTs = getms();
00465 _u8 recvBuffer[sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)];
00466 _u8 *nodeBuffer = (_u8*)&node;
00467 _u32 waitTime;
00468
00469 while ((waitTime=getms() - startTs) <= timeout) {
00470 size_t remainSize = sizeof(rplidar_response_ultra_capsule_measurement_nodes_t) - recvPos;
00471 size_t recvSize;
00472
00473 bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
00474 if(!ans)
00475 {
00476 return RESULT_OPERATION_TIMEOUT;
00477 }
00478 if (recvSize > remainSize) recvSize = remainSize;
00479
00480 recvSize = _chanDev->recvdata(recvBuffer, recvSize);
00481
00482 for (size_t pos = 0; pos < recvSize; ++pos) {
00483 _u8 currentByte = recvBuffer[pos];
00484 switch (recvPos) {
00485 case 0:
00486 {
00487 _u8 tmp = (currentByte>>4);
00488 if ( tmp == RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1 ) {
00489
00490 }
00491 else {
00492 _is_previous_capsuledataRdy = false;
00493 continue;
00494 }
00495 }
00496 break;
00497 case 1:
00498 {
00499 _u8 tmp = (currentByte>>4);
00500 if (tmp == RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2) {
00501
00502 }
00503 else {
00504 recvPos = 0;
00505 _is_previous_capsuledataRdy = false;
00506 continue;
00507 }
00508 }
00509 break;
00510 }
00511 nodeBuffer[recvPos++] = currentByte;
00512 if (recvPos == sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
00513
00514 _u8 checksum = 0;
00515 _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
00516
00517 for (size_t cpos = offsetof(rplidar_response_ultra_capsule_measurement_nodes_t, start_angle_sync_q6);
00518 cpos < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t); ++cpos)
00519 {
00520 checksum ^= nodeBuffer[cpos];
00521 }
00522
00523 if (recvChecksum == checksum)
00524 {
00525
00526 if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
00527 {
00528
00529 _is_previous_capsuledataRdy = false;
00530 return RESULT_OK;
00531 }
00532 return RESULT_OK;
00533 }
00534 _is_previous_capsuledataRdy = false;
00535 return RESULT_INVALID_DATA;
00536 }
00537 }
00538 }
00539 _is_previous_capsuledataRdy = false;
00540 return RESULT_OPERATION_TIMEOUT;
00541 }
00542
00543 u_result RPlidarDriverImplCommon::_cacheScanData()
00544 {
00545 rplidar_response_measurement_node_t local_buf[128];
00546 size_t count = 128;
00547 rplidar_response_measurement_node_hq_t local_scan[MAX_SCAN_NODES];
00548 size_t scan_count = 0;
00549 u_result ans;
00550 memset(local_scan, 0, sizeof(local_scan));
00551
00552 _waitScanData(local_buf, count);
00553
00554 while(_isScanning)
00555 {
00556 if (IS_FAIL(ans=_waitScanData(local_buf, count))) {
00557 if (ans != RESULT_OPERATION_TIMEOUT) {
00558 _isScanning = false;
00559 return RESULT_OPERATION_FAIL;
00560 }
00561 }
00562
00563 for (size_t pos = 0; pos < count; ++pos)
00564 {
00565 if (local_buf[pos].sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
00566 {
00567
00568
00569 if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
00570 _lock.lock();
00571 memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
00572 _cached_scan_node_hq_count = scan_count;
00573 _dataEvt.set();
00574 _lock.unlock();
00575 }
00576 scan_count = 0;
00577 }
00578
00579 rplidar_response_measurement_node_hq_t nodeHq;
00580 convert(local_buf[pos], nodeHq);
00581 local_scan[scan_count++] = nodeHq;
00582 if (scan_count == _countof(local_scan)) scan_count-=1;
00583
00584
00585 {
00586 rp::hal::AutoLocker l(_lock);
00587 _cached_scan_node_hq_buf_for_interval_retrieve[_cached_scan_node_hq_count_for_interval_retrieve++] = nodeHq;
00588 if(_cached_scan_node_hq_count_for_interval_retrieve == _countof(_cached_scan_node_hq_buf_for_interval_retrieve)) _cached_scan_node_hq_count_for_interval_retrieve-=1;
00589 }
00590 }
00591 }
00592 _isScanning = false;
00593 return RESULT_OK;
00594 }
00595
00596 u_result RPlidarDriverImplCommon::startScanNormal(bool force, _u32 timeout)
00597 {
00598 u_result ans;
00599 if (!isConnected()) return RESULT_OPERATION_FAIL;
00600 if (_isScanning) return RESULT_ALREADY_DONE;
00601
00602 stop();
00603
00604 {
00605 rp::hal::AutoLocker l(_lock);
00606
00607 if (IS_FAIL(ans = _sendCommand(force?RPLIDAR_CMD_FORCE_SCAN:RPLIDAR_CMD_SCAN))) {
00608 return ans;
00609 }
00610
00611
00612 rplidar_ans_header_t response_header;
00613 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
00614 return ans;
00615 }
00616
00617
00618 if (response_header.type != RPLIDAR_ANS_TYPE_MEASUREMENT) {
00619 return RESULT_INVALID_DATA;
00620 }
00621
00622 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
00623 if (header_size < sizeof(rplidar_response_measurement_node_t)) {
00624 return RESULT_INVALID_DATA;
00625 }
00626
00627 _isScanning = true;
00628 _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheScanData);
00629 if (_cachethread.getHandle() == 0) {
00630 return RESULT_OPERATION_FAIL;
00631 }
00632 }
00633 return RESULT_OK;
00634 }
00635
00636 u_result RPlidarDriverImplCommon::checkExpressScanSupported(bool & support, _u32 timeout)
00637 {
00638 DEPRECATED_WARN("checkExpressScanSupported(bool&,_u32)", "getAllSupportedScanModes()");
00639
00640 rplidar_response_device_info_t devinfo;
00641
00642 support = false;
00643 u_result ans = getDeviceInfo(devinfo, timeout);
00644
00645 if (IS_FAIL(ans)) return ans;
00646
00647 if (devinfo.firmware_version >= ((0x1<<8) | 17)) {
00648 support = true;
00649 rplidar_response_sample_rate_t sample_rate;
00650 getSampleDuration_uS(sample_rate);
00651 _cached_sampleduration_express = sample_rate.express_sample_duration_us;
00652 _cached_sampleduration_std = sample_rate.std_sample_duration_us;
00653 }
00654
00655 return RESULT_OK;
00656 }
00657
00658 u_result RPlidarDriverImplCommon::_cacheCapsuledScanData()
00659 {
00660 rplidar_response_capsule_measurement_nodes_t capsule_node;
00661 rplidar_response_measurement_node_hq_t local_buf[128];
00662 size_t count = 128;
00663 rplidar_response_measurement_node_hq_t local_scan[MAX_SCAN_NODES];
00664 size_t scan_count = 0;
00665 u_result ans;
00666 memset(local_scan, 0, sizeof(local_scan));
00667
00668 _waitCapsuledNode(capsule_node);
00669
00670
00671
00672
00673 while(_isScanning)
00674 {
00675 if (IS_FAIL(ans=_waitCapsuledNode(capsule_node))) {
00676 if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
00677 _isScanning = false;
00678 return RESULT_OPERATION_FAIL;
00679 } else {
00680
00681 continue;
00682 }
00683 }
00684 switch (_cached_express_flag)
00685 {
00686 case 0:
00687 _capsuleToNormal(capsule_node, local_buf, count);
00688 break;
00689 case 1:
00690 _dense_capsuleToNormal(capsule_node, local_buf, count);
00691 break;
00692 }
00693
00694
00695 for (size_t pos = 0; pos < count; ++pos)
00696 {
00697 if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
00698 {
00699
00700
00701 if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
00702 _lock.lock();
00703 memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
00704 _cached_scan_node_hq_count = scan_count;
00705 _dataEvt.set();
00706 _lock.unlock();
00707 }
00708 scan_count = 0;
00709 }
00710 local_scan[scan_count++] = local_buf[pos];
00711 if (scan_count == _countof(local_scan)) scan_count-=1;
00712
00713
00714 {
00715 rp::hal::AutoLocker l(_lock);
00716 _cached_scan_node_hq_buf_for_interval_retrieve[_cached_scan_node_hq_count_for_interval_retrieve++] = local_buf[pos];
00717 if(_cached_scan_node_hq_count_for_interval_retrieve == _countof(_cached_scan_node_hq_buf_for_interval_retrieve)) _cached_scan_node_hq_count_for_interval_retrieve-=1;
00718 }
00719 }
00720 }
00721 _isScanning = false;
00722
00723 return RESULT_OK;
00724 }
00725
00726 u_result RPlidarDriverImplCommon::_cacheUltraCapsuledScanData()
00727 {
00728 rplidar_response_ultra_capsule_measurement_nodes_t ultra_capsule_node;
00729 rplidar_response_measurement_node_hq_t local_buf[128];
00730 size_t count = 128;
00731 rplidar_response_measurement_node_hq_t local_scan[MAX_SCAN_NODES];
00732 size_t scan_count = 0;
00733 u_result ans;
00734 memset(local_scan, 0, sizeof(local_scan));
00735
00736 _waitUltraCapsuledNode(ultra_capsule_node);
00737
00738 while(_isScanning)
00739 {
00740 if (IS_FAIL(ans=_waitUltraCapsuledNode(ultra_capsule_node))) {
00741 if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
00742 _isScanning = false;
00743 return RESULT_OPERATION_FAIL;
00744 } else {
00745
00746 continue;
00747 }
00748 }
00749
00750 _ultraCapsuleToNormal(ultra_capsule_node, local_buf, count);
00751
00752 for (size_t pos = 0; pos < count; ++pos)
00753 {
00754 if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
00755 {
00756
00757
00758 if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
00759 _lock.lock();
00760 memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
00761 _cached_scan_node_hq_count = scan_count;
00762 _dataEvt.set();
00763 _lock.unlock();
00764 }
00765 scan_count = 0;
00766 }
00767 local_scan[scan_count++] = local_buf[pos];
00768 if (scan_count == _countof(local_scan)) scan_count-=1;
00769
00770
00771 {
00772 rp::hal::AutoLocker l(_lock);
00773 _cached_scan_node_hq_buf_for_interval_retrieve[_cached_scan_node_hq_count_for_interval_retrieve++] = local_buf[pos];
00774 if(_cached_scan_node_hq_count_for_interval_retrieve == _countof(_cached_scan_node_hq_buf_for_interval_retrieve)) _cached_scan_node_hq_count_for_interval_retrieve-=1;
00775 }
00776 }
00777 }
00778
00779 _isScanning = false;
00780
00781 return RESULT_OK;
00782 }
00783
00784 void RPlidarDriverImplCommon::_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
00785 {
00786 nodeCount = 0;
00787 if (_is_previous_capsuledataRdy) {
00788 int diffAngle_q8;
00789 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF)<< 2);
00790 int prevStartAngle_q8 = ((_cached_previous_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
00791
00792 diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
00793 if (prevStartAngle_q8 > currentStartAngle_q8) {
00794 diffAngle_q8 += (360<<8);
00795 }
00796
00797 int angleInc_q16 = (diffAngle_q8 << 3);
00798 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
00799 for (size_t pos = 0; pos < _countof(_cached_previous_capsuledata.cabins); ++pos)
00800 {
00801 int dist_q2[2];
00802 int angle_q6[2];
00803 int syncBit[2];
00804
00805 dist_q2[0] = (_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0xFFFC);
00806 dist_q2[1] = (_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0xFFFC);
00807
00808 int angle_offset1_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 & 0xF) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0x3)<<4));
00809 int angle_offset2_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 >> 4) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0x3)<<4));
00810
00811 angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3<<13))>>10);
00812 syncBit[0] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
00813 currentAngle_raw_q16 += angleInc_q16;
00814
00815
00816 angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3<<13))>>10);
00817 syncBit[1] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
00818 currentAngle_raw_q16 += angleInc_q16;
00819
00820 for (int cpos = 0; cpos < 2; ++cpos) {
00821
00822 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360<<6);
00823 if (angle_q6[cpos] >= (360<<6)) angle_q6[cpos] -= (360<<6);
00824
00825 rplidar_response_measurement_node_hq_t node;
00826
00827 node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
00828 node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
00829 node.quality = dist_q2[cpos] ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
00830 node.dist_mm_q2 = dist_q2[cpos];
00831
00832 nodebuffer[nodeCount++] = node;
00833 }
00834
00835 }
00836 }
00837
00838 _cached_previous_capsuledata = capsule;
00839 _is_previous_capsuledataRdy = true;
00840 }
00841
00842 void RPlidarDriverImplCommon::_dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
00843 {
00844 const rplidar_response_dense_capsule_measurement_nodes_t *dense_capsule = reinterpret_cast<const rplidar_response_dense_capsule_measurement_nodes_t*>(&capsule);
00845 nodeCount = 0;
00846 if (_is_previous_capsuledataRdy) {
00847 int diffAngle_q8;
00848 int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
00849 int prevStartAngle_q8 = ((_cached_previous_dense_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
00850
00851 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
00852 if (prevStartAngle_q8 > currentStartAngle_q8) {
00853 diffAngle_q8 += (360 << 8);
00854 }
00855
00856 int angleInc_q16 = (diffAngle_q8 << 8)/40;
00857 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
00858 for (size_t pos = 0; pos < _countof(_cached_previous_dense_capsuledata.cabins); ++pos)
00859 {
00860 int dist_q2;
00861 int angle_q6;
00862 int syncBit;
00863 const int dist = static_cast<const int>(_cached_previous_dense_capsuledata.cabins[pos].distance);
00864 dist_q2 = dist << 2;
00865 angle_q6 = (currentAngle_raw_q16 >> 10);
00866 syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
00867 currentAngle_raw_q16 += angleInc_q16;
00868
00869 if (angle_q6 < 0) angle_q6 += (360 << 6);
00870 if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
00871
00872
00873
00874 rplidar_response_measurement_node_hq_t node;
00875
00876 node.angle_z_q14 = _u16((angle_q6 << 8) / 90);
00877 node.flag = (syncBit | ((!syncBit) << 1));
00878 node.quality = dist_q2 ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
00879 node.dist_mm_q2 = dist_q2;
00880
00881 nodebuffer[nodeCount++] = node;
00882
00883
00884 }
00885 }
00886
00887 _cached_previous_dense_capsuledata = *dense_capsule;
00888 _is_previous_capsuledataRdy = true;
00889 }
00890
00891 u_result RPlidarDriverImplCommon::_cacheHqScanData()
00892 {
00893 rplidar_response_hq_capsule_measurement_nodes_t hq_node;
00894 rplidar_response_measurement_node_hq_t local_buf[128];
00895 size_t count = 128;
00896 rplidar_response_measurement_node_hq_t local_scan[MAX_SCAN_NODES];
00897 size_t scan_count = 0;
00898 u_result ans;
00899 memset(local_scan, 0, sizeof(local_scan));
00900 _waitHqNode(hq_node);
00901 while (_isScanning) {
00902 if (IS_FAIL(ans = _waitHqNode(hq_node))) {
00903 if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
00904 _isScanning = false;
00905 return RESULT_OPERATION_FAIL;
00906 }
00907 else {
00908
00909 continue;
00910 }
00911 }
00912
00913 _HqToNormal(hq_node, local_buf, count);
00914 for (size_t pos = 0; pos < count; ++pos)
00915 {
00916 if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
00917 {
00918
00919 if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
00920 _lock.lock();
00921 memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(rplidar_response_measurement_node_hq_t));
00922 _cached_scan_node_hq_count = scan_count;
00923 _dataEvt.set();
00924 _lock.unlock();
00925 }
00926 scan_count = 0;
00927 }
00928 local_scan[scan_count++] = local_buf[pos];
00929 if (scan_count == _countof(local_scan)) scan_count -= 1;
00930
00931 {
00932 rp::hal::AutoLocker l(_lock);
00933 _cached_scan_node_hq_buf_for_interval_retrieve[_cached_scan_node_hq_count_for_interval_retrieve++] = local_buf[pos];
00934 if (_cached_scan_node_hq_count_for_interval_retrieve == _countof(_cached_scan_node_hq_buf_for_interval_retrieve)) _cached_scan_node_hq_count_for_interval_retrieve -= 1;
00935 }
00936 }
00937
00938 }
00939 return RESULT_OK;
00940 }
00941
00942
00943 static _u32 table[256];
00944
00945
00946 static _u32 _bitrev(_u32 input, _u16 bw)
00947 {
00948 _u16 i;
00949 _u32 var;
00950 var = 0;
00951 for (i = 0; i<bw; i++){
00952 if (input & 0x01)
00953 {
00954 var |= 1 << (bw - 1 - i);
00955 }
00956 input >>= 1;
00957 }
00958 return var;
00959 }
00960
00961
00962 static void _crc32_init(_u32 poly)
00963 {
00964 _u16 i;
00965 _u16 j;
00966 _u32 c;
00967
00968 poly = _bitrev(poly, 32);
00969 for (i = 0; i<256; i++){
00970 c = i;
00971 for (j = 0; j<8; j++){
00972 if (c & 1)
00973 c = poly ^ (c >> 1);
00974 else
00975 c = c >> 1;
00976 }
00977 table[i] = c;
00978 }
00979 }
00980
00981 static _u32 _crc32cal(_u32 crc, void* input, _u16 len)
00982 {
00983 _u16 i;
00984 _u8 index;
00985 _u8* pch;
00986 pch = (unsigned char*)input;
00987 _u8 leftBytes = 4 - len & 0x3;
00988
00989 for (i = 0; i<len; i++){
00990 index = (unsigned char)(crc^*pch);
00991 crc = (crc >> 8) ^ table[index];
00992 pch++;
00993 }
00994
00995 for (i = 0; i < leftBytes; i++) {
00996 index = (unsigned char)(crc^0);
00997 crc = (crc >> 8) ^ table[index];
00998 }
00999 return crc^0xffffffff;
01000 }
01001
01002
01003 static u_result _crc32(_u8 *ptr, _u32 len) {
01004 static _u8 tmp;
01005 if (tmp != 1) {
01006 _crc32_init(0x4C11DB7);
01007 tmp = 1;
01008 }
01009
01010 return _crc32cal(0xFFFFFFFF, ptr,len);
01011 }
01012
01013 u_result RPlidarDriverImplCommon::_waitHqNode(rplidar_response_hq_capsule_measurement_nodes_t & node, _u32 timeout)
01014 {
01015 if (!_isConnected) {
01016 return RESULT_OPERATION_FAIL;
01017 }
01018
01019 int recvPos = 0;
01020 _u32 startTs = getms();
01021 _u8 recvBuffer[sizeof(rplidar_response_hq_capsule_measurement_nodes_t)];
01022 _u8 *nodeBuffer = (_u8*)&node;
01023 _u32 waitTime;
01024
01025 while ((waitTime=getms() - startTs) <= timeout) {
01026 size_t remainSize = sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - recvPos;
01027 size_t recvSize;
01028
01029 bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
01030 if(!ans)
01031 {
01032 return RESULT_OPERATION_TIMEOUT;
01033 }
01034 if (recvSize > remainSize) recvSize = remainSize;
01035
01036 recvSize = _chanDev->recvdata(recvBuffer, recvSize);
01037
01038 for (size_t pos = 0; pos < recvSize; ++pos) {
01039 _u8 currentByte = recvBuffer[pos];
01040 switch (recvPos) {
01041 case 0:
01042 {
01043 _u8 tmp = (currentByte);
01044 if ( tmp == RPLIDAR_RESP_MEASUREMENT_HQ_SYNC ) {
01045
01046 }
01047 else {
01048 recvPos = 0;
01049 _is_previous_HqdataRdy = false;
01050 continue;
01051 }
01052 }
01053 break;
01054 case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1 - 4:
01055 {
01056
01057 }
01058 break;
01059 case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1:
01060 {
01061
01062 }
01063 break;
01064 }
01065 nodeBuffer[recvPos++] = currentByte;
01066 if (recvPos == sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
01067 _u32 crcCalc2 = _crc32(nodeBuffer, sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 4);
01068
01069 if(crcCalc2 == node.crc32){
01070 _is_previous_HqdataRdy = true;
01071 return RESULT_OK;
01072 }
01073 else {
01074 _is_previous_HqdataRdy = false;
01075 return RESULT_INVALID_DATA;
01076 }
01077
01078 }
01079 }
01080 }
01081 _is_previous_HqdataRdy = false;
01082 return RESULT_OPERATION_TIMEOUT;
01083 }
01084
01085 void RPlidarDriverImplCommon::_HqToNormal(const rplidar_response_hq_capsule_measurement_nodes_t & node_hq, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
01086 {
01087 nodeCount = 0;
01088 if (_is_previous_HqdataRdy) {
01089 for (size_t pos = 0; pos < _countof(_cached_previous_Hqdata.node_hq); ++pos)
01090 {
01091 nodebuffer[nodeCount++] = node_hq.node_hq[pos];
01092 }
01093 }
01094 _cached_previous_Hqdata = node_hq;
01095 _is_previous_HqdataRdy = true;
01096
01097 }
01098
01099
01100 static _u32 _varbitscale_decode(_u32 scaled, _u32 & scaleLevel)
01101 {
01102 static const _u32 VBS_SCALED_BASE[] = {
01103 RPLIDAR_VARBITSCALE_X16_DEST_VAL,
01104 RPLIDAR_VARBITSCALE_X8_DEST_VAL,
01105 RPLIDAR_VARBITSCALE_X4_DEST_VAL,
01106 RPLIDAR_VARBITSCALE_X2_DEST_VAL,
01107 0,
01108 };
01109
01110 static const _u32 VBS_SCALED_LVL[] = {
01111 4,
01112 3,
01113 2,
01114 1,
01115 0,
01116 };
01117
01118 static const _u32 VBS_TARGET_BASE[] = {
01119 (0x1 << RPLIDAR_VARBITSCALE_X16_SRC_BIT),
01120 (0x1 << RPLIDAR_VARBITSCALE_X8_SRC_BIT),
01121 (0x1 << RPLIDAR_VARBITSCALE_X4_SRC_BIT),
01122 (0x1 << RPLIDAR_VARBITSCALE_X2_SRC_BIT),
01123 0,
01124 };
01125
01126 for (size_t i = 0; i < _countof(VBS_SCALED_BASE); ++i)
01127 {
01128 int remain = ((int)scaled - (int)VBS_SCALED_BASE[i]);
01129 if (remain >= 0) {
01130 scaleLevel = VBS_SCALED_LVL[i];
01131 return VBS_TARGET_BASE[i] + (remain << scaleLevel);
01132 }
01133 }
01134 return 0;
01135 }
01136
01137 void RPlidarDriverImplCommon::_ultraCapsuleToNormal(const rplidar_response_ultra_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
01138 {
01139 nodeCount = 0;
01140 if (_is_previous_capsuledataRdy) {
01141 int diffAngle_q8;
01142 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
01143 int prevStartAngle_q8 = ((_cached_previous_ultracapsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
01144
01145 diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
01146 if (prevStartAngle_q8 > currentStartAngle_q8) {
01147 diffAngle_q8 += (360 << 8);
01148 }
01149
01150 int angleInc_q16 = (diffAngle_q8 << 3) / 3;
01151 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
01152 for (size_t pos = 0; pos < _countof(_cached_previous_ultracapsuledata.ultra_cabins); ++pos)
01153 {
01154 int dist_q2[3];
01155 int angle_q6[3];
01156 int syncBit[3];
01157
01158
01159 _u32 combined_x3 = _cached_previous_ultracapsuledata.ultra_cabins[pos].combined_x3;
01160
01161
01162 int dist_major = (combined_x3 & 0xFFF);
01163
01164
01165
01166
01167 int dist_predict1 = (((int)(combined_x3 << 10)) >> 22);
01168 int dist_predict2 = (((int)combined_x3) >> 22);
01169
01170 int dist_major2;
01171
01172 _u32 scalelvl1, scalelvl2;
01173
01174
01175 if (pos == _countof(_cached_previous_ultracapsuledata.ultra_cabins) - 1)
01176 {
01177 dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
01178 }
01179 else {
01180 dist_major2 = (_cached_previous_ultracapsuledata.ultra_cabins[pos + 1].combined_x3 & 0xFFF);
01181 }
01182
01183
01184 dist_major = _varbitscale_decode(dist_major, scalelvl1);
01185 dist_major2 = _varbitscale_decode(dist_major2, scalelvl2);
01186
01187
01188 int dist_base1 = dist_major;
01189 int dist_base2 = dist_major2;
01190
01191 if ((!dist_major) && dist_major2) {
01192 dist_base1 = dist_major2;
01193 scalelvl1 = scalelvl2;
01194 }
01195
01196
01197 dist_q2[0] = (dist_major << 2);
01198 if ((dist_predict1 == 0xFFFFFE00) || (dist_predict1 == 0x1FF)) {
01199 dist_q2[1] = 0;
01200 } else {
01201 dist_predict1 = (dist_predict1 << scalelvl1);
01202 dist_q2[1] = (dist_predict1 + dist_base1) << 2;
01203
01204 }
01205
01206 if ((dist_predict2 == 0xFFFFFE00) || (dist_predict2 == 0x1FF)) {
01207 dist_q2[2] = 0;
01208 } else {
01209 dist_predict2 = (dist_predict2 << scalelvl2);
01210 dist_q2[2] = (dist_predict2 + dist_base2) << 2;
01211 }
01212
01213
01214 for (int cpos = 0; cpos < 3; ++cpos)
01215 {
01216
01217 syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
01218
01219 int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
01220
01221 if (dist_q2[cpos] >= (50 * 4))
01222 {
01223 const int k1 = 98361;
01224 const int k2 = int(k1 / dist_q2[cpos]);
01225
01226 offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
01227 }
01228
01229 angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
01230 currentAngle_raw_q16 += angleInc_q16;
01231
01232 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
01233 if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
01234
01235 rplidar_response_measurement_node_hq_t node;
01236
01237 node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
01238 node.quality = dist_q2[cpos] ? (0x2F << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
01239 node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
01240 node.dist_mm_q2 = dist_q2[cpos];
01241
01242 nodebuffer[nodeCount++] = node;
01243 }
01244
01245 }
01246 }
01247
01248 _cached_previous_ultracapsuledata = capsule;
01249 _is_previous_capsuledataRdy = true;
01250 }
01251
01252 u_result RPlidarDriverImplCommon::checkSupportConfigCommands(bool& outSupport, _u32 timeoutInMs)
01253 {
01254 u_result ans;
01255
01256 rplidar_response_device_info_t devinfo;
01257 ans = getDeviceInfo(devinfo, timeoutInMs);
01258 if (IS_FAIL(ans)) return ans;
01259
01260
01261 if (devinfo.firmware_version >= ((0x1 << 8) | 24)) {
01262 outSupport = true;
01263 }
01264 return ans;
01265 }
01266
01267 u_result RPlidarDriverImplCommon::getLidarConf(_u32 type, std::vector<_u8> &outputBuf, const std::vector<_u8> &reserve, _u32 timeout)
01268 {
01269 rplidar_payload_get_scan_conf_t query;
01270 memset(&query, 0, sizeof(query));
01271 query.type = type;
01272 int sizeVec = reserve.size();
01273
01274 int maxLen = sizeof(query.reserved) / sizeof(query.reserved[0]);
01275 if (sizeVec > maxLen) sizeVec = maxLen;
01276
01277 if (sizeVec > 0)
01278 memcpy(query.reserved, &reserve[0], reserve.size());
01279
01280 u_result ans;
01281 {
01282 rp::hal::AutoLocker l(_lock);
01283 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_LIDAR_CONF, &query, sizeof(query)))) {
01284 return ans;
01285 }
01286
01287
01288 rplidar_ans_header_t response_header;
01289 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
01290 return ans;
01291 }
01292
01293
01294 if (response_header.type != RPLIDAR_ANS_TYPE_GET_LIDAR_CONF) {
01295 return RESULT_INVALID_DATA;
01296 }
01297
01298 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
01299 if (header_size < sizeof(type)) {
01300 return RESULT_INVALID_DATA;
01301 }
01302
01303 if (!_chanDev->waitfordata(header_size, timeout)) {
01304 return RESULT_OPERATION_TIMEOUT;
01305 }
01306
01307 std::vector<_u8> dataBuf;
01308 dataBuf.resize(header_size);
01309 _chanDev->recvdata(reinterpret_cast<_u8 *>(&dataBuf[0]), header_size);
01310
01311
01312 _u32 replyType = -1;
01313 memcpy(&replyType, &dataBuf[0], sizeof(type));
01314 if (replyType != type) {
01315 return RESULT_INVALID_DATA;
01316 }
01317
01318
01319 int payLoadLen = header_size - sizeof(type);
01320
01321
01322 if (payLoadLen <= 0) {
01323 return RESULT_INVALID_DATA;
01324 }
01325
01326 outputBuf.resize(payLoadLen);
01327 memcpy(&outputBuf[0], &dataBuf[0] + sizeof(type), payLoadLen);
01328 }
01329 return ans;
01330 }
01331
01332 u_result RPlidarDriverImplCommon::getTypicalScanMode(_u16& outMode, _u32 timeoutInMs)
01333 {
01334 u_result ans;
01335 std::vector<_u8> answer;
01336 bool lidarSupportConfigCmds = false;
01337 ans = checkSupportConfigCommands(lidarSupportConfigCmds);
01338 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01339
01340 if (lidarSupportConfigCmds)
01341 {
01342 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_TYPICAL, answer, std::vector<_u8>(), timeoutInMs);
01343 if (IS_FAIL(ans)) {
01344 return ans;
01345 }
01346 if (answer.size() < sizeof(_u16)) {
01347 return RESULT_INVALID_DATA;
01348 }
01349
01350 const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
01351 outMode = *p_answer;
01352 return ans;
01353 }
01354
01355 else
01356 {
01357 outMode = RPLIDAR_CONF_SCAN_COMMAND_EXPRESS;
01358 return ans;
01359 }
01360 return ans;
01361 }
01362
01363 u_result RPlidarDriverImplCommon::getLidarSampleDuration(float& sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs)
01364 {
01365 u_result ans;
01366 std::vector<_u8> reserve(2);
01367 memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
01368
01369 std::vector<_u8> answer;
01370 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE, answer, reserve, timeoutInMs);
01371 if (IS_FAIL(ans))
01372 {
01373 return ans;
01374 }
01375 if (answer.size() < sizeof(_u32))
01376 {
01377 return RESULT_INVALID_DATA;
01378 }
01379 const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
01380 sampleDurationRes = (float)(*result >> 8);
01381 return ans;
01382 }
01383
01384 u_result RPlidarDriverImplCommon::getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs)
01385 {
01386 u_result ans;
01387 std::vector<_u8> reserve(2);
01388 memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
01389
01390 std::vector<_u8> answer;
01391 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE, answer, reserve, timeoutInMs);
01392 if (IS_FAIL(ans))
01393 {
01394 return ans;
01395 }
01396 if (answer.size() < sizeof(_u32))
01397 {
01398 return RESULT_INVALID_DATA;
01399 }
01400 const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
01401 maxDistance = (float)(*result >> 8);
01402 return ans;
01403 }
01404
01405 u_result RPlidarDriverImplCommon::getScanModeAnsType(_u8 &ansType, _u16 scanModeID, _u32 timeoutInMs)
01406 {
01407 u_result ans;
01408 std::vector<_u8> reserve(2);
01409 memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
01410
01411 std::vector<_u8> answer;
01412 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_ANS_TYPE, answer, reserve, timeoutInMs);
01413 if (IS_FAIL(ans))
01414 {
01415 return ans;
01416 }
01417 if (answer.size() < sizeof(_u8))
01418 {
01419 return RESULT_INVALID_DATA;
01420 }
01421 const _u8 *result = reinterpret_cast<const _u8*>(&answer[0]);
01422 ansType = *result;
01423 return ans;
01424 }
01425
01426 u_result RPlidarDriverImplCommon::getScanModeName(char* modeName, _u16 scanModeID, _u32 timeoutInMs)
01427 {
01428 u_result ans;
01429 std::vector<_u8> reserve(2);
01430 memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
01431
01432 std::vector<_u8> answer;
01433 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_NAME, answer, reserve, timeoutInMs);
01434 if (IS_FAIL(ans))
01435 {
01436 return ans;
01437 }
01438 int len = answer.size();
01439 if (0 == len) return RESULT_INVALID_DATA;
01440 memcpy(modeName, &answer[0], len);
01441 return ans;
01442 }
01443
01444 u_result RPlidarDriverImplCommon::getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs)
01445 {
01446 u_result ans;
01447 bool confProtocolSupported = false;
01448 ans = checkSupportConfigCommands(confProtocolSupported);
01449 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01450
01451 if (confProtocolSupported)
01452 {
01453
01454 _u16 modeCount;
01455 ans = getScanModeCount(modeCount);
01456 if (IS_FAIL(ans))
01457 {
01458 return RESULT_INVALID_DATA;
01459 }
01460
01461 for (_u16 i = 0; i < modeCount; i++)
01462 {
01463 RplidarScanMode scanModeInfoTmp;
01464 memset(&scanModeInfoTmp, 0, sizeof(scanModeInfoTmp));
01465 scanModeInfoTmp.id = i;
01466 ans = getLidarSampleDuration(scanModeInfoTmp.us_per_sample, i);
01467 if (IS_FAIL(ans))
01468 {
01469 return RESULT_INVALID_DATA;
01470 }
01471 ans = getMaxDistance(scanModeInfoTmp.max_distance, i);
01472 if (IS_FAIL(ans))
01473 {
01474 return RESULT_INVALID_DATA;
01475 }
01476 ans = getScanModeAnsType(scanModeInfoTmp.ans_type, i);
01477 if (IS_FAIL(ans))
01478 {
01479 return RESULT_INVALID_DATA;
01480 }
01481 ans = getScanModeName(scanModeInfoTmp.scan_mode, i);
01482 if (IS_FAIL(ans))
01483 {
01484 return RESULT_INVALID_DATA;
01485 }
01486 outModes.push_back(scanModeInfoTmp);
01487 }
01488 return ans;
01489 }
01490 else
01491 {
01492 rplidar_response_sample_rate_t sampleRateTmp;
01493 ans = getSampleDuration_uS(sampleRateTmp);
01494 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01495
01496 bool ifSupportExpScan = false;
01497 ans = checkExpressScanSupported(ifSupportExpScan);
01498 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01499
01500 RplidarScanMode stdScanModeInfo;
01501 stdScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_STD;
01502 stdScanModeInfo.us_per_sample = sampleRateTmp.std_sample_duration_us;
01503 stdScanModeInfo.max_distance = 16;
01504 stdScanModeInfo.ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
01505 strcpy(stdScanModeInfo.scan_mode, "Standard");
01506 outModes.push_back(stdScanModeInfo);
01507 if (ifSupportExpScan)
01508 {
01509 RplidarScanMode expScanModeInfo;
01510 expScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_EXPRESS;
01511 expScanModeInfo.us_per_sample = sampleRateTmp.express_sample_duration_us;
01512 expScanModeInfo.max_distance = 16;
01513 expScanModeInfo.ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED;
01514 strcpy(expScanModeInfo.scan_mode, "Express");
01515 outModes.push_back(expScanModeInfo);
01516 }
01517 return ans;
01518 }
01519 return ans;
01520 }
01521
01522 u_result RPlidarDriverImplCommon::getScanModeCount(_u16& modeCount, _u32 timeoutInMs)
01523 {
01524 u_result ans;
01525 std::vector<_u8> answer;
01526 ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_COUNT, answer, std::vector<_u8>(), timeoutInMs);
01527
01528 if (IS_FAIL(ans)) {
01529 return ans;
01530 }
01531 if (answer.size() < sizeof(_u16)) {
01532 return RESULT_INVALID_DATA;
01533 }
01534 const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
01535 modeCount = *p_answer;
01536
01537 return ans;
01538 }
01539
01540
01541 u_result RPlidarDriverImplCommon::startScan(bool force, bool useTypicalScan, _u32 options, RplidarScanMode* outUsedScanMode)
01542 {
01543 u_result ans;
01544
01545 bool ifSupportLidarConf = false;
01546 ans = checkSupportConfigCommands(ifSupportLidarConf);
01547 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01548
01549 if (useTypicalScan)
01550 {
01551
01552 if (ifSupportLidarConf)
01553 {
01554 _u16 typicalMode;
01555 ans = getTypicalScanMode(typicalMode);
01556 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01557
01558
01559 return startScanExpress(false, typicalMode, 0, outUsedScanMode);
01560 }
01561
01562 else
01563 {
01564 bool isExpScanSupported = false;
01565 ans = checkExpressScanSupported(isExpScanSupported);
01566 if (IS_FAIL(ans)) {
01567 return ans;
01568 }
01569 if (isExpScanSupported)
01570 {
01571 return startScanExpress(false, RPLIDAR_CONF_SCAN_COMMAND_EXPRESS, 0, outUsedScanMode);
01572 }
01573 }
01574 }
01575
01576
01577 if(ifSupportLidarConf)
01578 {
01579 if(outUsedScanMode)
01580 {
01581 outUsedScanMode->id = RPLIDAR_CONF_SCAN_COMMAND_STD;
01582 ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
01583 if(IS_FAIL(ans))
01584 {
01585 return RESULT_INVALID_DATA;
01586 }
01587
01588 ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
01589 if(IS_FAIL(ans))
01590 {
01591 return RESULT_INVALID_DATA;
01592 }
01593
01594 ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
01595 if(IS_FAIL(ans))
01596 {
01597 return RESULT_INVALID_DATA;
01598 }
01599
01600 ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
01601 if(IS_FAIL(ans))
01602 {
01603 return RESULT_INVALID_DATA;
01604 }
01605 }
01606 }
01607 else
01608 {
01609 if(outUsedScanMode)
01610 {
01611 rplidar_response_sample_rate_t sampleRateTmp;
01612 ans = getSampleDuration_uS(sampleRateTmp);
01613 if(IS_FAIL(ans)) return RESULT_INVALID_DATA;
01614 outUsedScanMode->us_per_sample = sampleRateTmp.std_sample_duration_us;
01615 outUsedScanMode->max_distance = 16;
01616 outUsedScanMode->ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
01617 strcpy(outUsedScanMode->scan_mode, "Standard");
01618 }
01619 }
01620
01621 return startScanNormal(force);
01622 }
01623
01624 u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u32 options, RplidarScanMode* outUsedScanMode, _u32 timeout)
01625 {
01626 u_result ans;
01627 if (!isConnected()) return RESULT_OPERATION_FAIL;
01628 if (_isScanning) return RESULT_ALREADY_DONE;
01629
01630 stop();
01631
01632 if (scanMode == RPLIDAR_CONF_SCAN_COMMAND_STD)
01633 {
01634 return startScan(force, false, 0, outUsedScanMode);
01635 }
01636
01637
01638 bool ifSupportLidarConf = false;
01639 ans = checkSupportConfigCommands(ifSupportLidarConf);
01640 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01641
01642 if (outUsedScanMode)
01643 {
01644 outUsedScanMode->id = scanMode;
01645 if (ifSupportLidarConf)
01646 {
01647 ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
01648 if (IS_FAIL(ans))
01649 {
01650 return RESULT_INVALID_DATA;
01651 }
01652
01653 ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
01654 if (IS_FAIL(ans))
01655 {
01656 return RESULT_INVALID_DATA;
01657 }
01658
01659 ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
01660 if (IS_FAIL(ans))
01661 {
01662 return RESULT_INVALID_DATA;
01663 }
01664
01665 ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
01666 if (IS_FAIL(ans))
01667 {
01668 return RESULT_INVALID_DATA;
01669 }
01670
01671
01672 }
01673 else
01674 {
01675 rplidar_response_sample_rate_t sampleRateTmp;
01676 ans = getSampleDuration_uS(sampleRateTmp);
01677 if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
01678
01679 outUsedScanMode->us_per_sample = sampleRateTmp.express_sample_duration_us;
01680 outUsedScanMode->max_distance = 16;
01681 outUsedScanMode->ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED;
01682 strcpy(outUsedScanMode->scan_mode, "Express");
01683 }
01684 }
01685
01686
01687 _u8 scanAnsType;
01688 if (ifSupportLidarConf)
01689 {
01690 getScanModeAnsType(scanAnsType, scanMode);
01691 }
01692 else
01693 {
01694 scanAnsType = RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED;
01695 }
01696
01697 {
01698 rp::hal::AutoLocker l(_lock);
01699
01700 rplidar_payload_express_scan_t scanReq;
01701 memset(&scanReq, 0, sizeof(scanReq));
01702 if (scanMode != RPLIDAR_CONF_SCAN_COMMAND_STD && scanMode != RPLIDAR_CONF_SCAN_COMMAND_EXPRESS)
01703 scanReq.working_mode = _u8(scanMode);
01704 scanReq.working_flags = options;
01705
01706 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq)))) {
01707 return ans;
01708 }
01709
01710
01711 rplidar_ans_header_t response_header;
01712 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
01713 return ans;
01714 }
01715
01716
01717 if (response_header.type != scanAnsType) {
01718 return RESULT_INVALID_DATA;
01719 }
01720
01721 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
01722
01723 if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED)
01724 {
01725 if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
01726 return RESULT_INVALID_DATA;
01727 }
01728 _cached_express_flag = 0;
01729 _isScanning = true;
01730 _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheCapsuledScanData);
01731 }
01732 else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED)
01733 {
01734 if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
01735 return RESULT_INVALID_DATA;
01736 }
01737 _cached_express_flag = 1;
01738 _isScanning = true;
01739 _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheCapsuledScanData);
01740 }
01741 else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_HQ) {
01742 if (header_size < sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
01743 return RESULT_INVALID_DATA;
01744 }
01745 _isScanning = true;
01746 _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheHqScanData);
01747 }
01748 else
01749 {
01750 if (header_size < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
01751 return RESULT_INVALID_DATA;
01752 }
01753 _isScanning = true;
01754 _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheUltraCapsuledScanData);
01755 }
01756
01757 if (_cachethread.getHandle() == 0) {
01758 return RESULT_OPERATION_FAIL;
01759 }
01760 }
01761 return RESULT_OK;
01762 }
01763
01764 u_result RPlidarDriverImplCommon::stop(_u32 timeout)
01765 {
01766 u_result ans;
01767 _disableDataGrabbing();
01768
01769 {
01770 rp::hal::AutoLocker l(_lock);
01771
01772 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_STOP))) {
01773 return ans;
01774 }
01775 }
01776
01777 return RESULT_OK;
01778 }
01779
01780 u_result RPlidarDriverImplCommon::grabScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
01781 {
01782 DEPRECATED_WARN("grabScanData()", "grabScanDataHq()");
01783
01784 switch (_dataEvt.wait(timeout))
01785 {
01786 case rp::hal::Event::EVENT_TIMEOUT:
01787 count = 0;
01788 return RESULT_OPERATION_TIMEOUT;
01789 case rp::hal::Event::EVENT_OK:
01790 {
01791 if(_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT;
01792
01793 rp::hal::AutoLocker l(_lock);
01794
01795 size_t size_to_copy = min(count, _cached_scan_node_hq_count);
01796
01797 for (size_t i = 0; i < size_to_copy; i++)
01798 convert(_cached_scan_node_hq_buf[i], nodebuffer[i]);
01799
01800 count = size_to_copy;
01801 _cached_scan_node_hq_count = 0;
01802 }
01803 return RESULT_OK;
01804
01805 default:
01806 count = 0;
01807 return RESULT_OPERATION_FAIL;
01808 }
01809 }
01810
01811 u_result RPlidarDriverImplCommon::grabScanDataHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count, _u32 timeout)
01812 {
01813 switch (_dataEvt.wait(timeout))
01814 {
01815 case rp::hal::Event::EVENT_TIMEOUT:
01816 count = 0;
01817 return RESULT_OPERATION_TIMEOUT;
01818 case rp::hal::Event::EVENT_OK:
01819 {
01820 if (_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT;
01821
01822 rp::hal::AutoLocker l(_lock);
01823
01824 size_t size_to_copy = min(count, _cached_scan_node_hq_count);
01825 memcpy(nodebuffer, _cached_scan_node_hq_buf, size_to_copy * sizeof(rplidar_response_measurement_node_hq_t));
01826
01827 count = size_to_copy;
01828 _cached_scan_node_hq_count = 0;
01829 }
01830 return RESULT_OK;
01831
01832 default:
01833 count = 0;
01834 return RESULT_OPERATION_FAIL;
01835 }
01836 }
01837
01838 u_result RPlidarDriverImplCommon::getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count)
01839 {
01840 DEPRECATED_WARN("getScanDataWithInterval(rplidar_response_measurement_node_t*, size_t&)", "getScanDataWithInterval(rplidar_response_measurement_node_hq_t*, size_t&)");
01841
01842 size_t size_to_copy = 0;
01843 {
01844 rp::hal::AutoLocker l(_lock);
01845 if(_cached_scan_node_hq_count_for_interval_retrieve == 0)
01846 {
01847 return RESULT_OPERATION_TIMEOUT;
01848 }
01849
01850 size_to_copy = _cached_scan_node_hq_count_for_interval_retrieve;
01851 for (size_t i = 0; i < size_to_copy; i++)
01852 {
01853 convert(_cached_scan_node_hq_buf_for_interval_retrieve[i], nodebuffer[i]);
01854 }
01855 _cached_scan_node_hq_count_for_interval_retrieve = 0;
01856 }
01857 count = size_to_copy;
01858
01859 return RESULT_OK;
01860 }
01861
01862 u_result RPlidarDriverImplCommon::getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count)
01863 {
01864 size_t size_to_copy = 0;
01865 {
01866 rp::hal::AutoLocker l(_lock);
01867 if (_cached_scan_node_hq_count_for_interval_retrieve == 0)
01868 {
01869 return RESULT_OPERATION_TIMEOUT;
01870 }
01871
01872 size_to_copy = _cached_scan_node_hq_count_for_interval_retrieve;
01873 memcpy(nodebuffer, _cached_scan_node_hq_buf_for_interval_retrieve, size_to_copy * sizeof(rplidar_response_measurement_node_hq_t));
01874 _cached_scan_node_hq_count_for_interval_retrieve = 0;
01875 }
01876 count = size_to_copy;
01877
01878 return RESULT_OK;
01879 }
01880
01881 static inline float getAngle(const rplidar_response_measurement_node_t& node)
01882 {
01883 return (node.angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) / 64.f;
01884 }
01885
01886 static inline void setAngle(rplidar_response_measurement_node_t& node, float v)
01887 {
01888 _u16 checkbit = node.angle_q6_checkbit & RPLIDAR_RESP_MEASUREMENT_CHECKBIT;
01889 node.angle_q6_checkbit = (((_u16)(v * 64.0f)) << RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) | checkbit;
01890 }
01891
01892 static inline float getAngle(const rplidar_response_measurement_node_hq_t& node)
01893 {
01894 return node.angle_z_q14 * 90.f / 16384.f;
01895 }
01896
01897 static inline void setAngle(rplidar_response_measurement_node_hq_t& node, float v)
01898 {
01899 node.angle_z_q14 = _u32(v * 16384.f / 90.f);
01900 }
01901
01902 static inline _u16 getDistanceQ2(const rplidar_response_measurement_node_t& node)
01903 {
01904 return node.distance_q2;
01905 }
01906
01907 static inline _u32 getDistanceQ2(const rplidar_response_measurement_node_hq_t& node)
01908 {
01909 return node.dist_mm_q2;
01910 }
01911
01912 template <class TNode>
01913 static bool angleLessThan(const TNode& a, const TNode& b)
01914 {
01915 return getAngle(a) < getAngle(b);
01916 }
01917
01918 template < class TNode >
01919 static u_result ascendScanData_(TNode * nodebuffer, size_t count)
01920 {
01921 float inc_origin_angle = 360.f/count;
01922 size_t i = 0;
01923
01924
01925 for (i = 0; i < count; i++) {
01926 if(getDistanceQ2(nodebuffer[i]) == 0) {
01927 continue;
01928 } else {
01929 while(i != 0) {
01930 i--;
01931 float expect_angle = getAngle(nodebuffer[i+1]) - inc_origin_angle;
01932 if (expect_angle < 0.0f) expect_angle = 0.0f;
01933 setAngle(nodebuffer[i], expect_angle);
01934 }
01935 break;
01936 }
01937 }
01938
01939
01940 if (i == count) return RESULT_OPERATION_FAIL;
01941
01942
01943 for (i = count - 1; i >= 0; i--) {
01944 if(getDistanceQ2(nodebuffer[i]) == 0) {
01945 continue;
01946 } else {
01947 while(i != (count - 1)) {
01948 i++;
01949 float expect_angle = getAngle(nodebuffer[i-1]) + inc_origin_angle;
01950 if (expect_angle > 360.0f) expect_angle -= 360.0f;
01951 setAngle(nodebuffer[i], expect_angle);
01952 }
01953 break;
01954 }
01955 }
01956
01957
01958 float frontAngle = getAngle(nodebuffer[0]);
01959 for (i = 1; i < count; i++) {
01960 if(getDistanceQ2(nodebuffer[i]) == 0) {
01961 float expect_angle = frontAngle + i * inc_origin_angle;
01962 if (expect_angle > 360.0f) expect_angle -= 360.0f;
01963 setAngle(nodebuffer[i], expect_angle);
01964 }
01965 }
01966
01967
01968 std::sort(nodebuffer, nodebuffer + count, &angleLessThan<TNode>);
01969
01970 return RESULT_OK;
01971 }
01972
01973 u_result RPlidarDriverImplCommon::ascendScanData(rplidar_response_measurement_node_t * nodebuffer, size_t count)
01974 {
01975 DEPRECATED_WARN("ascendScanData(rplidar_response_measurement_node_t*, size_t)", "ascendScanData(rplidar_response_measurement_node_hq_t*, size_t)");
01976
01977 return ascendScanData_<rplidar_response_measurement_node_t>(nodebuffer, count);
01978 }
01979
01980 u_result RPlidarDriverImplCommon::ascendScanData(rplidar_response_measurement_node_hq_t * nodebuffer, size_t count)
01981 {
01982 return ascendScanData_<rplidar_response_measurement_node_hq_t>(nodebuffer, count);
01983 }
01984
01985 u_result RPlidarDriverImplCommon::_sendCommand(_u8 cmd, const void * payload, size_t payloadsize)
01986 {
01987 _u8 pkt_header[10];
01988 rplidar_cmd_packet_t * header = reinterpret_cast<rplidar_cmd_packet_t * >(pkt_header);
01989 _u8 checksum = 0;
01990
01991 if (!_isConnected) return RESULT_OPERATION_FAIL;
01992
01993 if (payloadsize && payload) {
01994 cmd |= RPLIDAR_CMDFLAG_HAS_PAYLOAD;
01995 }
01996
01997 header->syncByte = RPLIDAR_CMD_SYNC_BYTE;
01998 header->cmd_flag = cmd;
01999
02000
02001 _chanDev->senddata(pkt_header, 2) ;
02002
02003 if (cmd & RPLIDAR_CMDFLAG_HAS_PAYLOAD) {
02004 checksum ^= RPLIDAR_CMD_SYNC_BYTE;
02005 checksum ^= cmd;
02006 checksum ^= (payloadsize & 0xFF);
02007
02008
02009 for (size_t pos = 0; pos < payloadsize; ++pos) {
02010 checksum ^= ((_u8 *)payload)[pos];
02011 }
02012
02013
02014 _u8 sizebyte = payloadsize;
02015 _chanDev->senddata(&sizebyte, 1);
02016
02017
02018 _chanDev->senddata((const _u8 *)payload, sizebyte);
02019
02020
02021 _chanDev->senddata(&checksum, 1);
02022 }
02023
02024 return RESULT_OK;
02025 }
02026
02027 u_result RPlidarDriverImplCommon::getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout)
02028 {
02029 DEPRECATED_WARN("getSampleDuration_uS", "RplidarScanMode::us_per_sample");
02030
02031 if (!isConnected()) return RESULT_OPERATION_FAIL;
02032
02033 _disableDataGrabbing();
02034
02035 rplidar_response_device_info_t devinfo;
02036
02037 u_result ans = getDeviceInfo(devinfo, timeout);
02038
02039 rateInfo.express_sample_duration_us = _cached_sampleduration_express;
02040 rateInfo.std_sample_duration_us = _cached_sampleduration_std;
02041
02042 if (devinfo.firmware_version < ((0x1<<8) | 17)) {
02043
02044
02045 return RESULT_OK;
02046 }
02047
02048
02049 {
02050 rp::hal::AutoLocker l(_lock);
02051
02052 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_SAMPLERATE))) {
02053 return ans;
02054 }
02055
02056 rplidar_ans_header_t response_header;
02057 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
02058 return ans;
02059 }
02060
02061
02062 if (response_header.type != RPLIDAR_ANS_TYPE_SAMPLE_RATE) {
02063 return RESULT_INVALID_DATA;
02064 }
02065
02066 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
02067 if ( header_size < sizeof(rplidar_response_sample_rate_t)) {
02068 return RESULT_INVALID_DATA;
02069 }
02070
02071 if (!_chanDev->waitfordata(header_size, timeout)) {
02072 return RESULT_OPERATION_TIMEOUT;
02073 }
02074 _chanDev->recvdata(reinterpret_cast<_u8 *>(&rateInfo), sizeof(rateInfo));
02075 }
02076 return RESULT_OK;
02077 }
02078
02079 u_result RPlidarDriverImplCommon::checkMotorCtrlSupport(bool & support, _u32 timeout)
02080 {
02081 u_result ans;
02082 support = false;
02083
02084 if (!isConnected()) return RESULT_OPERATION_FAIL;
02085
02086 _disableDataGrabbing();
02087
02088 {
02089 rp::hal::AutoLocker l(_lock);
02090
02091 rplidar_payload_acc_board_flag_t flag;
02092 flag.reserved = 0;
02093
02094 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_ACC_BOARD_FLAG, &flag, sizeof(flag)))) {
02095 return ans;
02096 }
02097
02098 rplidar_ans_header_t response_header;
02099 if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
02100 return ans;
02101 }
02102
02103
02104 if (response_header.type != RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG) {
02105 return RESULT_INVALID_DATA;
02106 }
02107
02108 _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
02109 if ( header_size < sizeof(rplidar_response_acc_board_flag_t)) {
02110 return RESULT_INVALID_DATA;
02111 }
02112
02113 if (!_chanDev->waitfordata(header_size, timeout)) {
02114 return RESULT_OPERATION_TIMEOUT;
02115 }
02116 rplidar_response_acc_board_flag_t acc_board_flag;
02117 _chanDev->recvdata(reinterpret_cast<_u8 *>(&acc_board_flag), sizeof(acc_board_flag));
02118
02119 if (acc_board_flag.support_flag & RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK) {
02120 support = true;
02121 }
02122 }
02123 return RESULT_OK;
02124 }
02125
02126 u_result RPlidarDriverImplCommon::setMotorPWM(_u16 pwm)
02127 {
02128 u_result ans;
02129 rplidar_payload_motor_pwm_t motor_pwm;
02130 motor_pwm.pwm_value = pwm;
02131
02132 {
02133 rp::hal::AutoLocker l(_lock);
02134
02135 if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_SET_MOTOR_PWM,(const _u8 *)&motor_pwm, sizeof(motor_pwm)))) {
02136 return ans;
02137 }
02138 }
02139
02140 return RESULT_OK;
02141 }
02142
02143 u_result RPlidarDriverImplCommon::startMotor()
02144 {
02145 if (_isSupportingMotorCtrl) {
02146 setMotorPWM(DEFAULT_MOTOR_PWM);
02147 delay(500);
02148 return RESULT_OK;
02149 } else {
02150 rp::hal::AutoLocker l(_lock);
02151 _chanDev->clearDTR();
02152 delay(500);
02153 return RESULT_OK;
02154 }
02155 }
02156
02157 u_result RPlidarDriverImplCommon::stopMotor()
02158 {
02159 if (_isSupportingMotorCtrl) {
02160 setMotorPWM(0);
02161 delay(500);
02162 return RESULT_OK;
02163 } else {
02164 rp::hal::AutoLocker l(_lock);
02165 _chanDev->setDTR();
02166 delay(500);
02167 return RESULT_OK;
02168 }
02169 }
02170
02171 void RPlidarDriverImplCommon::_disableDataGrabbing()
02172 {
02173 _isScanning = false;
02174 _cachethread.join();
02175 }
02176
02177
02178
02179 RPlidarDriverSerial::RPlidarDriverSerial()
02180 {
02181 _chanDev = new SerialChannelDevice();
02182 }
02183
02184 RPlidarDriverSerial::~RPlidarDriverSerial()
02185 {
02186
02187 disconnect();
02188
02189 _chanDev->close();
02190 _chanDev->ReleaseRxTx();
02191 }
02192
02193 void RPlidarDriverSerial::disconnect()
02194 {
02195 if (!_isConnected) return ;
02196 stop();
02197 }
02198
02199 u_result RPlidarDriverSerial::connect(const char * port_path, _u32 baudrate, _u32 flag)
02200 {
02201 if (isConnected()) return RESULT_ALREADY_DONE;
02202
02203 if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
02204
02205 {
02206 rp::hal::AutoLocker l(_lock);
02207
02208
02209 if (!_chanDev->bind(port_path, baudrate) || !_chanDev->open()) {
02210 return RESULT_INVALID_DATA;
02211 }
02212 _chanDev->flush();
02213 }
02214
02215 _isConnected = true;
02216
02217 checkMotorCtrlSupport(_isSupportingMotorCtrl);
02218 stopMotor();
02219
02220 return RESULT_OK;
02221 }
02222
02223 RPlidarDriverTCP::RPlidarDriverTCP()
02224 {
02225 _chanDev = new TCPChannelDevice();
02226 }
02227
02228 RPlidarDriverTCP::~RPlidarDriverTCP()
02229 {
02230
02231 disconnect();
02232 }
02233
02234 void RPlidarDriverTCP::disconnect()
02235 {
02236 if (!_isConnected) return ;
02237 stop();
02238 _chanDev->close();
02239 }
02240
02241 u_result RPlidarDriverTCP::connect(const char * ipStr, _u32 port, _u32 flag)
02242 {
02243 if (isConnected()) return RESULT_ALREADY_DONE;
02244
02245 if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
02246
02247 {
02248 rp::hal::AutoLocker l(_lock);
02249
02250
02251 if(!_chanDev->bind(ipStr, port))
02252 return RESULT_INVALID_DATA;
02253 }
02254
02255 _isConnected = true;
02256
02257 checkMotorCtrlSupport(_isSupportingMotorCtrl);
02258 stopMotor();
02259
02260 return RESULT_OK;
02261 }
02262
02263 }}}