00001 /* 00002 * RPLIDAR SDK 00003 * 00004 * Copyright (c) 2009 - 2014 RoboPeak Team 00005 * http://www.robopeak.com 00006 * Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd. 00007 * http://www.slamtec.com 00008 * 00009 */ 00010 /* 00011 * Redistribution and use in source and binary forms, with or without 00012 * modification, are permitted provided that the following conditions are met: 00013 * 00014 * 1. Redistributions of source code must retain the above copyright notice, 00015 * this list of conditions and the following disclaimer. 00016 * 00017 * 2. Redistributions in binary form must reproduce the above copyright notice, 00018 * this list of conditions and the following disclaimer in the documentation 00019 * and/or other materials provided with the distribution. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00022 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 00023 * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 00024 * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00025 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 00026 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 00027 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 00028 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 00029 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 00030 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 00031 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00032 * 00033 */ 00034 00035 #pragma once 00036 00037 #include "rplidar_protocol.h" 00038 00039 // Commands 00040 //----------------------------------------- 00041 00042 // Commands without payload and response 00043 #define RPLIDAR_CMD_STOP 0x25 00044 #define RPLIDAR_CMD_SCAN 0x20 00045 #define RPLIDAR_CMD_FORCE_SCAN 0x21 00046 #define RPLIDAR_CMD_RESET 0x40 00047 00048 00049 // Commands without payload but have response 00050 #define RPLIDAR_CMD_GET_DEVICE_INFO 0x50 00051 #define RPLIDAR_CMD_GET_DEVICE_HEALTH 0x52 00052 00053 #define RPLIDAR_CMD_GET_SAMPLERATE 0x59 //added in fw 1.17 00054 00055 // Commands with payload and have response 00056 #define RPLIDAR_CMD_EXPRESS_SCAN 0x82 //added in fw 1.17 00057 00058 //add for A2 to set RPLIDAR motor pwm when using accessory board 00059 #define RPLIDAR_CMD_SET_MOTOR_PWM 0xF0 00060 #define RPLIDAR_CMD_GET_ACC_BOARD_FLAG 0xFF 00061 00062 #if defined(_WIN32) 00063 #pragma pack(1) 00064 #endif 00065 00066 00067 // Payloads 00068 // ------------------------------------------ 00069 #define RPLIDAR_EXPRESS_SCAN_MODE_NORMAL 0 00070 #define RPLIDAR_EXPRESS_SCAN_MODE_FIXANGLE 1 00071 typedef struct _rplidar_payload_express_scan_t { 00072 _u8 working_mode; 00073 _u32 reserved; 00074 } __attribute__((packed)) rplidar_payload_express_scan_t; 00075 00076 #define MAX_MOTOR_PWM 1023 00077 #define DEFAULT_MOTOR_PWM 660 00078 typedef struct _rplidar_payload_motor_pwm_t { 00079 _u16 pwm_value; 00080 } __attribute__((packed)) rplidar_payload_motor_pwm_t; 00081 00082 typedef struct _rplidar_payload_acc_board_flag_t { 00083 _u32 reserved; 00084 } __attribute__((packed)) rplidar_payload_acc_board_flag_t; 00085 00086 // Response 00087 // ------------------------------------------ 00088 #define RPLIDAR_ANS_TYPE_DEVINFO 0x4 00089 #define RPLIDAR_ANS_TYPE_DEVHEALTH 0x6 00090 00091 #define RPLIDAR_ANS_TYPE_MEASUREMENT 0x81 00092 // Added in FW ver 1.17 00093 #define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED 0x82 00094 00095 // Added in FW ver 1.17 00096 #define RPLIDAR_ANS_TYPE_SAMPLE_RATE 0x15 00097 00098 #define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG 0xFF 00099 00100 #define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK (0x1) 00101 typedef struct _rplidar_response_acc_board_flag_t { 00102 _u32 support_flag; 00103 } __attribute__((packed)) rplidar_response_acc_board_flag_t; 00104 00105 00106 #define RPLIDAR_STATUS_OK 0x0 00107 #define RPLIDAR_STATUS_WARNING 0x1 00108 #define RPLIDAR_STATUS_ERROR 0x2 00109 00110 #define RPLIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0) 00111 #define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2 00112 #define RPLIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0) 00113 #define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1 00114 00115 typedef struct _rplidar_response_sample_rate_t { 00116 _u16 std_sample_duration_us; 00117 _u16 express_sample_duration_us; 00118 } __attribute__((packed)) rplidar_response_sample_rate_t; 00119 00120 typedef struct _rplidar_response_measurement_node_t { 00121 _u8 sync_quality; // syncbit:1;syncbit_inverse:1;quality:6; 00122 _u16 angle_q6_checkbit; // check_bit:1;angle_q6:15; 00123 _u16 distance_q2; 00124 } __attribute__((packed)) rplidar_response_measurement_node_t; 00125 00126 //[distance_sync flags] 00127 #define RPLIDAR_RESP_MEASUREMENT_EXP_ANGLE_MASK (0x3) 00128 #define RPLIDAR_RESP_MEASUREMENT_EXP_DISTANCE_MASK (0xFC) 00129 00130 typedef struct _rplidar_response_cabin_nodes_t { 00131 _u16 distance_angle_1; // see [distance_sync flags] 00132 _u16 distance_angle_2; // see [distance_sync flags] 00133 _u8 offset_angles_q3; 00134 } __attribute__((packed)) rplidar_response_cabin_nodes_t; 00135 00136 00137 #define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1 0xA 00138 #define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2 0x5 00139 00140 #define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT (0x1<<15) 00141 00142 typedef struct _rplidar_response_capsule_measurement_nodes_t { 00143 _u8 s_checksum_1; // see [s_checksum_1] 00144 _u8 s_checksum_2; // see [s_checksum_1] 00145 _u16 start_angle_sync_q6; 00146 rplidar_response_cabin_nodes_t cabins[16]; 00147 } __attribute__((packed)) rplidar_response_capsule_measurement_nodes_t; 00148 00149 typedef struct _rplidar_response_device_info_t { 00150 _u8 model; 00151 _u16 firmware_version; 00152 _u8 hardware_version; 00153 _u8 serialnum[16]; 00154 } __attribute__((packed)) rplidar_response_device_info_t; 00155 00156 typedef struct _rplidar_response_device_health_t { 00157 _u8 status; 00158 _u16 error_code; 00159 } __attribute__((packed)) rplidar_response_device_health_t; 00160 00161 #if defined(_WIN32) 00162 #pragma pack() 00163 #endif