43 #define min(a,b) (((a) < (b)) ? (a) : (b)) 46 namespace rp {
namespace standalone{
namespace rplidar {
73 , _isSupportingMotorCtrl(false)
156 rplidar_ans_header_t response_header;
167 if ( header_size <
sizeof(rplidar_response_device_health_t)) {
174 _rxtx->
recvdata(reinterpret_cast<_u8 *>(&healthinfo),
sizeof(healthinfo));
194 rplidar_ans_header_t response_header;
205 if (header_size <
sizeof(rplidar_response_device_info_t)) {
221 frequency = 1000000.0f/(
count * sample_duration);
223 if (sample_duration <= 277) {
248 rplidar_ans_header_t response_header;
259 if (header_size <
sizeof(rplidar_response_measurement_node_t)) {
274 rplidar_response_device_info_t devinfo;
281 if (devinfo.firmware_version >= ((0x1<<8) | 17)) {
283 rplidar_response_sample_rate_t sample_rate;
303 rplidar_payload_express_scan_t scanReq;
305 scanReq.reserved = 0;
312 rplidar_ans_header_t response_header;
323 if (header_size <
sizeof(rplidar_response_capsule_measurement_nodes_t)) {
339 bool isExpressModeSupported;
342 if (autoExpressMode) {
347 if (isExpressModeSupported) {
373 rplidar_response_measurement_node_t local_buf[128];
376 size_t scan_count = 0;
378 memset(local_scan, 0,
sizeof(local_scan));
391 for (
size_t pos = 0; pos <
count; ++pos)
406 local_scan[scan_count++] = local_buf[pos];
407 if (scan_count ==
_countof(local_scan)) scan_count-=1;
419 int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF)<< 2);
422 diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
423 if (prevStartAngle_q8 > currentStartAngle_q8) {
424 diffAngle_q8 += (360<<8);
427 int angleInc_q16 = (diffAngle_q8 << 3);
428 int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
441 angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3<<13))>>10);
442 syncBit[0] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
443 currentAngle_raw_q16 += angleInc_q16;
446 angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3<<13))>>10);
447 syncBit[1] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
448 currentAngle_raw_q16 += angleInc_q16;
450 for (
int cpos = 0; cpos < 2; ++cpos) {
452 if (angle_q6[cpos] < 0) angle_q6[cpos] += (360<<6);
453 if (angle_q6[cpos] >= (360<<6)) angle_q6[cpos] -= (360<<6);
455 rplidar_response_measurement_node_t node;
457 node.sync_quality = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
460 node.angle_q6_checkbit = (1 | (angle_q6[cpos]<<1));
461 node.distance_q2 = dist_q2[cpos];
463 nodebuffer[nodeCount++] = node;
476 rplidar_response_capsule_measurement_nodes_t capsule_node;
477 rplidar_response_measurement_node_t local_buf[128];
480 size_t scan_count = 0;
482 memset(local_scan, 0,
sizeof(local_scan));
500 for (
size_t pos = 0; pos <
count; ++pos)
515 local_scan[scan_count++] = local_buf[pos];
516 if (scan_count ==
_countof(local_scan)) scan_count-=1;
540 count = size_to_copy;
553 float inc_origin_angle = 360.0f/
count;
557 for (i = 0; i <
count && nodebuffer[i].distance_q2 == 0; i++);
565 if (expect_angle < 0.0f) expect_angle = 0.0f;
571 for (i =
count - 1; nodebuffer[i].distance_q2 == 0; i--);
573 while(i != (
count - 1)) {
576 if (expect_angle > 360.0f) expect_angle -= 360.0f;
583 for (i = 1; i <
count; i++) {
585 float expect_angle = frontAngle + i * inc_origin_angle;
586 if (expect_angle > 360.0f) expect_angle -= 360.0f;
593 for (i = 0; i < (
count-1); i++){
594 for (
size_t j = (i+1); j <
count; j++){
596 rplidar_response_measurement_node_t temp = nodebuffer[i];
597 nodebuffer[i] = nodebuffer[j];
598 nodebuffer[j] = temp;
610 _u8 recvBuffer[
sizeof(rplidar_response_measurement_node_t)];
611 _u8 *nodeBuffer = (
_u8*)node;
614 while ((waitTime=
getms() - startTs) <= timeout) {
615 size_t remainSize =
sizeof(rplidar_response_measurement_node_t) - recvPos;
624 if (recvSize > remainSize) recvSize = remainSize;
628 for (
size_t pos = 0; pos < recvSize; ++pos) {
629 _u8 currentByte = recvBuffer[pos];
633 _u8 tmp = (currentByte>>1);
634 if ( (tmp ^ currentByte) & 0x1 ) {
653 nodeBuffer[recvPos++] = currentByte;
655 if (recvPos ==
sizeof(rplidar_response_measurement_node_t)) {
672 size_t recvNodeCount = 0;
677 while ((waitTime =
getms() - startTs) <= timeout && recvNodeCount <
count) {
678 rplidar_response_measurement_node_t node;
683 nodebuffer[recvNodeCount++] = node;
687 count = recvNodeCount;
696 _u8 recvBuffer[
sizeof(rplidar_response_capsule_measurement_nodes_t)];
697 _u8 *nodeBuffer = (
_u8*)&node;
700 while ((waitTime=
getms() - startTs) <= timeout) {
701 size_t remainSize =
sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
710 if (recvSize > remainSize) recvSize = remainSize;
714 for (
size_t pos = 0; pos < recvSize; ++pos) {
715 _u8 currentByte = recvBuffer[pos];
719 _u8 tmp = (currentByte>>4);
731 _u8 tmp = (currentByte>>4);
742 nodeBuffer[recvPos++] = currentByte;
744 if (recvPos ==
sizeof(rplidar_response_capsule_measurement_nodes_t)) {
747 _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2<<4));
749 cpos <
sizeof(rplidar_response_capsule_measurement_nodes_t); ++cpos)
751 checksum ^= nodeBuffer[cpos];
753 if (recvChecksum == checksum)
777 rplidar_cmd_packet_t *
header =
reinterpret_cast<rplidar_cmd_packet_t *
>(pkt_header);
782 if (payloadsize && payload) {
795 checksum ^= (payloadsize & 0xFF);
798 for (
size_t pos = 0; pos < payloadsize; ++pos) {
799 checksum ^= ((
_u8 *)payload)[pos];
803 _u8 sizebyte = payloadsize;
821 _u8 recvBuffer[
sizeof(rplidar_ans_header_t)];
825 while ((waitTime=
getms() - startTs) <= timeout) {
826 size_t remainSize =
sizeof(rplidar_ans_header_t) - recvPos;
835 if(recvSize > remainSize) recvSize = remainSize;
839 for (
size_t pos = 0; pos < recvSize; ++pos) {
840 _u8 currentByte = recvBuffer[pos];
855 headerBuffer[recvPos++] = currentByte;
857 if (recvPos ==
sizeof(rplidar_ans_header_t)) {
880 rplidar_response_device_info_t devinfo;
887 if (devinfo.firmware_version < ((0x1<<8) | 17)) {
901 rplidar_ans_header_t response_header;
912 if ( header_size <
sizeof(rplidar_response_sample_rate_t)) {
919 _rxtx->
recvdata(reinterpret_cast<_u8 *>(&rateInfo),
sizeof(rateInfo));
936 rplidar_payload_acc_board_flag_t flag;
943 rplidar_ans_header_t response_header;
954 if ( header_size <
sizeof(rplidar_response_acc_board_flag_t)) {
961 rplidar_response_acc_board_flag_t acc_board_flag;
962 _rxtx->
recvdata(reinterpret_cast<_u8 *>(&acc_board_flag),
sizeof(acc_board_flag));
974 rplidar_payload_motor_pwm_t motor_pwm;
975 motor_pwm.pwm_value = pwm;
virtual int recvdata(unsigned char *data, size_t size)=0
#define offsetof(_structure, _field)
void BASE_IMPEXP memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) MRPT_NO_THROWS
An OS and compiler independent version of "memcpy".
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT
#define CLASS_THREAD(c, x)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT
virtual bool bind(const char *portname, _u32 baudrate, _u32 flags=0)=0
RPlidarDriverSerialImpl()
bool _isSupportingMotorCtrl
GLuint GLuint GLsizei count
#define RPLIDAR_CMD_FORCE_SCAN
#define RPLIDAR_EXPRESS_SCAN_MODE_FIXANGLE
_u16 _cached_sampleduration_express
virtual u_result startScanNormal(bool force, _u32 timeout=DEFAULT_TIMEOUT)
virtual bool isConnected()
Returns TRUE when the connection has been established.
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
virtual u_result ascendScanData(rplidar_response_measurement_node_t *nodebuffer, size_t count)
Ascending the scan data according to the angle value in the scan.
void _capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_t *nodebuffer, size_t &nodeCount)
virtual u_result getFrequency(bool inExpressMode, size_t count, float &frequency, bool &is4kmode)
Calcuate RPLIDAR's current scanning frequency from the given scan data Please refer to the applicatio...
#define RPLIDAR_ANS_TYPE_SAMPLE_RATE
size_t _cached_scan_node_count
void set(bool isSignal=true)
virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT)
Get the sample duration information of the RPLIDAR.
#define RPLIDAR_ANS_HEADER_SIZE_MASK
virtual u_result connect(const char *port_path, _u32 baudrate, _u32 flag)
Open the specified serial port and connect to a target RPLIDAR device.
virtual u_result startScanExpress(bool fixedAngle, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMD_GET_DEVICE_INFO
#define RPLIDAR_ANS_TYPE_DEVHEALTH
#define RPLIDAR_CMD_SYNC_BYTE
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT
virtual int senddata(const unsigned char *data, size_t size)=0
static serial_rxtx * CreateRxTx()
#define RESULT_INSUFFICIENT_MEMORY
#define RPLIDAR_ANS_SYNC_BYTE1
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_CMD_GET_SAMPLERATE
static void ReleaseRxTx(serial_rxtx *)
rplidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
virtual u_result grabScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
Wait and grab a complete 0-360 degree scan data previously received.
u_result _cacheCapsuledScanData()
virtual u_result stopMotor()
Stop RPLIDAR's motor when using accessory board.
u_result join(unsigned long timeout=-1)
#define RPLIDAR_CMD_RESET
nv_oem6_header_t header
Novatel frame: NV_OEM6_BESTPOS.
#define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK
#define RPLIDAR_CMDFLAG_HAS_PAYLOAD
#define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG
bool _is_previous_capsuledataRdy
virtual u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
Check whether the device support motor control.
virtual u_result startScan(bool force=false, bool autoExpressMode=true)
Ask the RPLIDAR core system to enter the scan mode(Normal/Express, Express mode is 4k mode) A backgro...
#define RPLIDAR_CMD_SET_MOTOR_PWM
#define RPLIDAR_CMD_EXPRESS_SCAN
rp::hal::serial_rxtx * _rxtx
virtual u_result startMotor()
Start RPLIDAR's motor when using accessory board.
virtual u_result setMotorPWM(_u16 pwm)
Set the RPLIDAR's motor pwm when using accessory board, currently valid for A2 only.
Locker::LOCK_STATUS lock(unsigned long timeout=0xFFFFFFFF)
u_result _sendCommand(_u8 cmd, const void *payload=NULL, size_t payloadsize=0)
u_result _waitResponseHeader(rplidar_ans_header_t *header, _u32 timeout=DEFAULT_TIMEOUT)
#define RESULT_OPERATION_TIMEOUT
u_result _waitNode(rplidar_response_measurement_node_t *node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_ANS_TYPE_MEASUREMENT
#define RPLIDAR_CMD_GET_ACC_BOARD_FLAG
virtual u_result checkExpressScanSupported(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
Check whether the device support express mode.
#define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT
virtual void clearDTR()=0
virtual u_result getDeviceInfo(rplidar_response_device_info_t &, _u32 timeout=DEFAULT_TIMEOUT)
Get the device information of the RPLIDAR include the serial number, firmware version, device model etc.
virtual int waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=NULL)=0
virtual ~RPlidarDriverSerialImpl()
virtual u_result reset(_u32 timeout=DEFAULT_TIMEOUT)
Ask the RPLIDAR core system to reset it self The host system can use the Reset operation to help RPLI...
rplidar_response_measurement_node_t _cached_scan_node_buf[2048]
u_result _cacheScanData()
unsigned long wait(unsigned long timeout=0xFFFFFFFF)
u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1
#define DEFAULT_MOTOR_PWM
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)
Ask the RPLIDAR core system to stop the current scan operation and enter idle state.
virtual u_result getHealth(rplidar_response_device_health_t &, _u32 timeout=DEFAULT_TIMEOUT)
Retrieve the health status of the RPLIDAR The host system can use this operation to check whether RPL...
_u16 _cached_sampleduration_std
#define RESULT_OPERATION_FAIL
#define RESULT_ALREADY_DONE
virtual void flush(_u32 flags)=0
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2
#define RPLIDAR_CMD_GET_DEVICE_HEALTH
void _disableDataGrabbing()
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
Create an RPLIDAR Driver Instance This interface should be invoked first before any other operations...
#define RPLIDAR_EXPRESS_SCAN_MODE_NORMAL
#define RPLIDAR_ANS_SYNC_BYTE2
rp::hal::Thread _cachethread
#define RESULT_INVALID_DATA
static void DisposeDriver(RPlidarDriver *drv)
Dispose the RPLIDAR Driver Instance specified by the drv parameter Applications should invoke this in...
#define RPLIDAR_ANS_TYPE_DEVINFO
u_result _waitScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)