├── CMakeLists.txt ├── LICENSE ├── Lidar ├── CMakeLists.txt ├── DeviceException.h ├── Drivers │ ├── CMakeLists.txt │ └── YDLidar │ │ ├── CMakeLists.txt │ │ ├── locker.h │ │ ├── thread.h │ │ ├── timer.h │ │ ├── unix_timer.cpp │ │ ├── win_timer.cpp │ │ ├── ydlidar_driver.cpp │ │ └── ydlidar_driver.h ├── LIDARDevice.h └── LIDARDriverInterface.h ├── README.md ├── Samples ├── CMakeLists.txt ├── lidar.ini ├── test.cpp └── test1.cpp ├── Serial ├── .gitignore ├── CMakeLists.txt ├── common.h ├── impl │ ├── unix │ │ ├── list_ports_linux.cpp │ │ ├── unix.h │ │ ├── unix_serial.cpp │ │ └── unix_serial.h │ └── windows │ │ ├── list_ports_win.cpp │ │ ├── win.h │ │ ├── win_serial.cpp │ │ └── win_serial.h ├── lock.c ├── lock.h ├── serial.cpp └── serial.h ├── Utils.h ├── config.h.in ├── image ├── image.png ├── index-X4.jpg ├── step1.png ├── step2.png ├── step3.png ├── step4.png ├── step5.png └── step6.png ├── simpleini ├── CMakeLists.txt ├── ConvertUTF.c ├── ConvertUTF.h ├── LICENCE.txt ├── README.md └── SimpleIni.h ├── startup └── initenv.sh └── ydlidar_sdk.pdf /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #/***************************************************************************** 2 | #* EAI TOF LIDAR DRIVER * 3 | #* Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | #* * 5 | #* This file is part of EAI TOF LIDAR DRIVER. * 6 | #* * 7 | #* @file CMakeLists.txt * 8 | #* @brief * 9 | #* Details. * 10 | #* * 11 | #* @author Tony.Yang * 12 | #* @email chushuifurong618@eaibot.com * 13 | #* @version 1.0.0(版本号) * 14 | #* @date chushuifurong618@eaibot.com * 15 | #* * 16 | #* * 17 | #*----------------------------------------------------------------------------* 18 | #* Remark : Description * 19 | #*----------------------------------------------------------------------------* 20 | #* Change History : * 21 | #* | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.0.0 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | cmake_minimum_required(VERSION 2.8) 28 | project( YDLIDAR_DRIVER ) 29 | set(LIDAR_VERSION_MAJOR 1) 30 | set(LIDAR_VERSION_MIDOR 3) 31 | set(LIDAR_VERSION_MINOR 8) 32 | set(LIDAR_VERSION ${LIDAR_VERSION_MAJOR}.${LIDAR_VERSION_MIDOR}.${LIDAR_VERSION_MINOR}) 33 | set( SDK_VERSION 1..3.8 ) 34 | 35 | message("SDK VERSION: ${SDK_VERSION}") 36 | message("LIDAR VERSION: ${LIDAR_VERSION}") 37 | 38 | 39 | # Policy CMP0023 allows to mix old and new interfaces of target_link_libraries 40 | cmake_policy(SET CMP0023 OLD) 41 | cmake_policy(SET CMP0022 OLD) 42 | 43 | if(POLICY CMP0042) 44 | cmake_policy(SET CMP0042 NEW) # MACOSX_RPATH 45 | endif() 46 | 47 | string(TOLOWER ${PROJECT_NAME} LIBRARY_NAME) 48 | 49 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall") 50 | 51 | ############################################################################# 52 | #option 53 | option( BUILD_SHARED_LIBS "Build shared libraries." ON ) 54 | OPTION( BUILD_EXAMPLE "Build example application" ON ) 55 | 56 | ############################################################################# 57 | # Find required libraries 58 | 59 | ############################################################################# 60 | # HAL macros for driver writers. 61 | set( HAL_DIR ${CMAKE_CURRENT_SOURCE_DIR} ) 62 | 63 | macro( add_to_hal_include_dirs ) 64 | foreach( dir ${ARGN} ) 65 | set_property( GLOBAL APPEND PROPERTY P_INCLUDE_DIRS "${dir}" ) 66 | endforeach() 67 | endmacro() 68 | 69 | 70 | macro( add_to_hal_libraries ) 71 | foreach( lib ${ARGN} ) 72 | # Process targets correctly 73 | if (TARGET ${lib}) 74 | # If the library is NOT imported, ie is in this project, we 75 | # want to depend on it directly rather than through its path 76 | get_target_property(is_lib_imported ${lib} IMPORTED) 77 | if (NOT ${is_lib_imported}) 78 | set_property( GLOBAL APPEND PROPERTY P_LIBRARIES "${lib}" ) 79 | else() 80 | # For imported targets, we just want to depend on the library directly 81 | get_target_property(libpath ${lib} LOCATION) 82 | if (libpath) 83 | set_property( GLOBAL APPEND PROPERTY P_LIBRARIES "${libpath}" ) 84 | # This shouldn't really happen, but let's cover our bases. 85 | else() 86 | set_property( GLOBAL APPEND PROPERTY P_LIBRARIES "${lib}" ) 87 | endif() 88 | endif() 89 | else() # Just add the direct path/flag to the list 90 | set_property( GLOBAL APPEND PROPERTY P_LIBRARIES "${lib}" ) 91 | endif() 92 | endforeach() 93 | 94 | endmacro() 95 | 96 | 97 | macro( add_to_hal_sources ) 98 | file(RELATIVE_PATH _relPath "${HAL_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") 99 | foreach(_src ${ARGN}) 100 | if(_relPath) 101 | set_property( GLOBAL APPEND PROPERTY P_SOURCES "${_relPath}/${_src}" ) 102 | else() 103 | set_property( GLOBAL APPEND PROPERTY P_SOURCES "${_src}" ) 104 | endif() 105 | endforeach() 106 | endmacro() 107 | 108 | macro( add_to_hal_headers ) 109 | file(RELATIVE_PATH _relPath "${HAL_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}") 110 | foreach(_hdr ${ARGN}) 111 | if(_relPath) 112 | set_property( GLOBAL APPEND PROPERTY P_HEADERS "${_relPath}/${_hdr}" ) 113 | else() 114 | set_property( GLOBAL APPEND PROPERTY P_HEADERS "${_hdr}" ) 115 | endif() 116 | endforeach() 117 | endmacro() 118 | 119 | macro( hal_set_compile_flags file flags ) 120 | set_property( GLOBAL APPEND PROPERTY COMPILER_OPTS_SOURCES "${file}" ) 121 | set_property( GLOBAL APPEND PROPERTY COMPILER_OPTS_FLAGS "${flags}" ) 122 | endmacro() 123 | 124 | 125 | macro(subdirlist result curdir) 126 | file(GLOB children RELATIVE ${curdir} ${curdir}/*) 127 | set(dirlist "") 128 | foreach(child ${children}) 129 | if( NOT child STREQUAL "CMakeFiles" ) 130 | if(IS_DIRECTORY ${curdir}/${child}) 131 | set(dirlist ${dirlist} ${child}) 132 | endif() 133 | endif() 134 | endforeach() 135 | set(${result} ${dirlist}) 136 | endmacro() 137 | 138 | ############################################################################# 139 | # Add Devices 140 | add_subdirectory( Lidar ) 141 | add_subdirectory( Serial ) 142 | add_subdirectory( simpleini ) 143 | 144 | if( BUILD_EXAMPLE ) 145 | add_subdirectory( Samples ) 146 | endif( BUILD_EXAMPLE) 147 | 148 | if( BUILD_SHARED_LIBS ) 149 | add_definitions(-DYDLIDAR_API_EXPORTS) 150 | else( BUILD_SHARED_LIBS ) 151 | add_definitions(-DYDLIDAR_API_STATIC) 152 | endif( BUILD_SHARED_LIBS ) 153 | 154 | add_to_hal_headers(Utils.h) 155 | 156 | ############################################################################# 157 | # Setup libraries 158 | 159 | get_property( INTERNAL_INC GLOBAL PROPERTY P_INCLUDE_DIRS ) 160 | get_property( INTERNAL_LIBS GLOBAL PROPERTY P_LIBRARIES ) 161 | get_property( HAL_SOURCES GLOBAL PROPERTY P_SOURCES ) 162 | get_property( HAL_HEADERS GLOBAL PROPERTY P_HEADERS ) 163 | 164 | # this is a horrible hack in order to set compiler flag properties to individual files 165 | get_property( C_O_S GLOBAL PROPERTY COMPILER_OPTS_SOURCES ) 166 | get_property( C_O_F GLOBAL PROPERTY COMPILER_OPTS_FLAGS ) 167 | 168 | list(LENGTH C_O_S len_c_o_s ) 169 | math(EXPR len_c_o_s "${len_c_o_s} - 1" ) 170 | 171 | foreach(val RANGE ${len_c_o_s} ) 172 | list(GET C_O_S ${val} source ) 173 | list(GET C_O_F ${val} flag ) 174 | set_source_files_properties( ${source} PROPERTIES COMPILE_FLAGS ${flag} ) 175 | endforeach() 176 | 177 | ########################################################################## 178 | 179 | include_directories(${CMAKE_SOURCE_DIR} ${CMAKE_BINARY_DIR} ) 180 | include_directories( ${LIB_INC_DIR} ) 181 | include_directories( ${INTERNAL_INC} ) 182 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/Lidar ) 183 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/Serial ) 184 | 185 | set(HAL_LIBS 186 | ${INTERNAL_LIBS} 187 | ${LINK_LIBS} 188 | CACHE STRING "HAL required libraries" 189 | ) 190 | 191 | list( REMOVE_ITEM HAL_LIBS "debug" ) 192 | list( REMOVE_ITEM HAL_LIBS "optimized" ) 193 | 194 | set(HAL_INCLUDES 195 | ${LIB_INC_DIR} 196 | ${USER_INC} 197 | CACHE STRING "HAL required includes" ) 198 | 199 | add_library(ydlidar_driver SHARED ${HAL_SOURCES} ${HAL_HEADERS}) 200 | add_library(ydlidar_driver_static STATIC ${HAL_SOURCES} ${HAL_HEADERS}) 201 | 202 | SET_TARGET_PROPERTIES(ydlidar_driver_static PROPERTIES OUTPUT_NAME "ydlidar_driver") 203 | SET_TARGET_PROPERTIES(ydlidar_driver PROPERTIES CLEAN_DIRECT_OUTPUT 1) 204 | SET_TARGET_PROPERTIES(ydlidar_driver_static PROPERTIES CLEAN_DIRECT_OUTPUT 1) 205 | 206 | target_link_libraries( ydlidar_driver ${HAL_LIBS} ) 207 | target_link_libraries( ydlidar_driver_static ${HAL_LIBS} ) 208 | 209 | IF (WIN32) 210 | target_link_libraries(ydlidar_driver setupapi) 211 | target_link_libraries(ydlidar_driver_static setupapi) 212 | 213 | ELSE() 214 | target_link_libraries(ydlidar_driver rt pthread) 215 | target_link_libraries(ydlidar_driver_static rt pthread) 216 | 217 | ENDIF() 218 | 219 | ######################################################## 220 | ## Create configure file for inclusion in library 221 | configure_file("${CMAKE_CURRENT_SOURCE_DIR}/config.h.in" 222 | "${CMAKE_CURRENT_BINARY_DIR}/config.h" ) 223 | 224 | set( GENERATED_HEADERS ${CMAKE_CURRENT_BINARY_DIR}/config.h) 225 | 226 | include_directories( ${CMAKE_BINARY_DIR} ) 227 | 228 | 229 | -------------------------------------------------------------------------------- /Lidar/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #/***************************************************************************** 2 | #* EAI TOF LIDAR DRIVER * 3 | #* Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | #* * 5 | #* This file is part of EAI TOF LIDAR DRIVER. * 6 | #* * 7 | #* @file CMakeLists.txt * 8 | #* @brief * 9 | #* Details. * 10 | #* * 11 | #* @author Tony.Yang * 12 | #* @email chushuifurong618@eaibot.com * 13 | #* @version 1.0.0(版本号) * 14 | #* @date chushuifurong618@eaibot.com * 15 | #* * 16 | #* * 17 | #*----------------------------------------------------------------------------* 18 | #* Remark : Description * 19 | #*----------------------------------------------------------------------------* 20 | #* Change History : * 21 | #* | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.0.0 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR} ) 28 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/Drivers ) 29 | 30 | set(HDRS 31 | LIDARDevice.h 32 | LIDARDriverInterface.h 33 | DeviceException.h 34 | ) 35 | 36 | add_to_hal_headers( ${HDRS} ) 37 | 38 | add_subdirectory( Drivers ) 39 | -------------------------------------------------------------------------------- /Lidar/DeviceException.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file DeviceException.h * 8 | * @brief Device exception description * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #include 30 | #include 31 | 32 | namespace ydlidar { 33 | 34 | struct DeviceException : std::exception 35 | { 36 | DeviceException(std::string str) : desc(str) {} 37 | DeviceException(std::string str, std::string detail) { 38 | desc = str + "\n\t" + detail; 39 | } 40 | ~DeviceException() throw() {} 41 | const char* what() const throw() { return desc.c_str(); } 42 | std::string desc; 43 | }; 44 | 45 | struct TimeoutException : std::exception 46 | { 47 | TimeoutException(std::string str) : desc(str) {} 48 | TimeoutException(std::string str, std::string detail) { 49 | desc = str + "\n\t" + detail; 50 | } 51 | ~TimeoutException() throw() {} 52 | const char* what() const throw() { return desc.c_str(); } 53 | std::string desc; 54 | }; 55 | 56 | 57 | struct CorruptedDataException : std::exception 58 | { 59 | CorruptedDataException(std::string str) : desc(str) {} 60 | CorruptedDataException(std::string str, std::string detail) { 61 | desc = str + "\n\t" + detail; 62 | } 63 | ~CorruptedDataException() throw() {} 64 | const char* what() const throw() { return desc.c_str(); } 65 | std::string desc; 66 | }; 67 | 68 | struct DeviceInformationException : std::exception 69 | { 70 | DeviceInformationException(std::string str) : desc(str) {} 71 | DeviceInformationException(std::string str, std::string detail) { 72 | desc = str + "\n\t" + detail; 73 | } 74 | ~DeviceInformationException() throw() {} 75 | const char* what() const throw() { return desc.c_str(); } 76 | std::string desc; 77 | }; 78 | } 79 | -------------------------------------------------------------------------------- /Lidar/Drivers/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #/***************************************************************************** 2 | #* EAI TOF LIDAR DRIVER * 3 | #* Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | #* * 5 | #* This file is part of EAI TOF LIDAR DRIVER. * 6 | #* * 7 | #* @file CMakeLists.txt * 8 | #* @brief * 9 | #* Details. * 10 | #* * 11 | #* @author Tony.Yang * 12 | #* @email chushuifurong618@eaibot.com * 13 | #* @version 1.0.0(版本号) * 14 | #* @date chushuifurong618@eaibot.com * 15 | #* * 16 | #* * 17 | #*----------------------------------------------------------------------------* 18 | #* Remark : Description * 19 | #*----------------------------------------------------------------------------* 20 | #* Change History : * 21 | #* | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.0.0 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | 28 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR} ) 29 | 30 | subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) 31 | 32 | foreach(subdir ${SUBDIRS}) 33 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/${subdir} ) 34 | 35 | add_subdirectory(${subdir}) 36 | endforeach() 37 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #/***************************************************************************** 2 | #* EAI TOF LIDAR DRIVER * 3 | #* Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | #* * 5 | #* This file is part of EAI TOF LIDAR DRIVER. * 6 | #* * 7 | #* @file CMakeLists.txt * 8 | #* @brief * 9 | #* Details. * 10 | #* * 11 | #* @author Tony.Yang * 12 | #* @email chushuifurong618@eaibot.com * 13 | #* @version 1.0.0(版本号) * 14 | #* @date chushuifurong618@eaibot.com * 15 | #* * 16 | #* * 17 | #*----------------------------------------------------------------------------* 18 | #* Remark : Description * 19 | #*----------------------------------------------------------------------------* 20 | #* Change History : * 21 | #* | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.0.0 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | 28 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR} ) 29 | 30 | list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}) 31 | add_to_hal_sources( ydlidar_driver.cpp ) 32 | add_to_hal_headers(ydlidar_driver.h timer.h locker.h thread.h) 33 | 34 | IF (WIN32) 35 | add_to_hal_sources(win_timer.cpp) 36 | ELSE() 37 | add_to_hal_sources(unix_timer.cpp) 38 | ENDIF() 39 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/locker.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #ifdef _WIN32 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #else 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #endif 18 | 19 | 20 | class Locker 21 | { 22 | public: 23 | enum LOCK_STATUS { 24 | LOCK_OK = 0, 25 | LOCK_TIMEOUT = -1, 26 | LOCK_FAILED = -2 27 | }; 28 | 29 | Locker(){ 30 | #ifdef _WIN32 31 | _lock = NULL; 32 | #endif 33 | init(); 34 | } 35 | 36 | ~Locker(){ 37 | release(); 38 | } 39 | 40 | Locker::LOCK_STATUS lock(unsigned long timeout = 0xFFFFFFFF) { 41 | #ifdef _WIN32 42 | switch (WaitForSingleObject(_lock, timeout==0xFFFFFFF?INFINITE:(DWORD)timeout)) { 43 | case WAIT_ABANDONED: 44 | return LOCK_FAILED; 45 | case WAIT_OBJECT_0: 46 | return LOCK_OK; 47 | case WAIT_TIMEOUT: 48 | return LOCK_TIMEOUT; 49 | } 50 | 51 | #else 52 | #ifdef _MACOS 53 | if (timeout !=0 ) { 54 | if (pthread_mutex_lock(&_lock) == 0) return LOCK_OK; 55 | } 56 | #else 57 | if (timeout == 0xFFFFFFFF){ 58 | if (pthread_mutex_lock(&_lock) == 0) return LOCK_OK; 59 | } 60 | #endif 61 | else if (timeout == 0) { 62 | if (pthread_mutex_trylock(&_lock) == 0) return LOCK_OK; 63 | } 64 | #ifndef _MACOS 65 | else{ 66 | timespec wait_time; 67 | timeval now; 68 | gettimeofday(&now,NULL); 69 | 70 | wait_time.tv_sec = timeout/1000 + now.tv_sec; 71 | wait_time.tv_nsec = (timeout%1000)*1000000 + now.tv_usec*1000; 72 | 73 | if (wait_time.tv_nsec >= 1000000000){ 74 | ++wait_time.tv_sec; 75 | wait_time.tv_nsec -= 1000000000; 76 | } 77 | 78 | #if !defined(__ANDROID__) 79 | 80 | switch (pthread_mutex_timedlock(&_lock,&wait_time)){ 81 | case 0: 82 | return LOCK_OK; 83 | case ETIMEDOUT: 84 | return LOCK_TIMEOUT; 85 | } 86 | 87 | #else 88 | struct timeval timenow; 89 | struct timespec sleepytime; 90 | /* This is just to avoid a completely busy wait */ 91 | sleepytime.tv_sec = 0; 92 | sleepytime.tv_nsec = 10000000; /* 10ms */ 93 | 94 | while (pthread_mutex_trylock (&_lock) == EBUSY) { 95 | gettimeofday (&timenow, NULL); 96 | 97 | if (timenow.tv_sec >= wait_time.tv_sec && 98 | (timenow.tv_usec * 1000) >= wait_time.tv_nsec) { 99 | return LOCK_TIMEOUT; 100 | } 101 | 102 | nanosleep (&sleepytime, NULL); 103 | } 104 | 105 | return LOCK_OK; 106 | 107 | #endif 108 | 109 | } 110 | #endif 111 | #endif 112 | 113 | return LOCK_FAILED; 114 | } 115 | 116 | 117 | void unlock(){ 118 | #ifdef _WIN32 119 | ReleaseMutex(_lock); 120 | #else 121 | pthread_mutex_unlock(&_lock); 122 | #endif 123 | } 124 | 125 | #ifdef _WIN32 126 | HANDLE getLockHandle(){ 127 | return _lock; 128 | } 129 | #else 130 | pthread_mutex_t *getLockHandle(){ 131 | return &_lock; 132 | } 133 | #endif 134 | 135 | 136 | 137 | protected: 138 | void init(){ 139 | #ifdef _WIN32 140 | _lock = CreateMutex(NULL,FALSE,NULL); 141 | #else 142 | pthread_mutex_init(&_lock, NULL); 143 | #endif 144 | } 145 | 146 | void release(){ 147 | unlock(); 148 | #ifdef _WIN32 149 | 150 | if(_lock){ 151 | CloseHandle(_lock); 152 | } 153 | _lock = NULL; 154 | #else 155 | pthread_mutex_destroy(&_lock); 156 | #endif 157 | } 158 | 159 | #ifdef _WIN32 160 | HANDLE _lock; 161 | #else 162 | pthread_mutex_t _lock; 163 | #endif 164 | }; 165 | 166 | 167 | class Event 168 | { 169 | public: 170 | 171 | enum { 172 | EVENT_OK = 1, 173 | EVENT_TIMEOUT = 2, 174 | EVENT_FAILED = 0, 175 | }; 176 | 177 | explicit Event(bool isAutoReset = true, bool isSignal = false) 178 | #ifdef _WIN32 179 | : _event(NULL) 180 | #else 181 | : _is_signalled(isSignal) 182 | , _isAutoReset(isAutoReset) 183 | #endif 184 | { 185 | #ifdef _WIN32 186 | _event = CreateEvent(NULL, isAutoReset?FALSE:TRUE, isSignal?TRUE:FALSE, NULL); 187 | #else 188 | pthread_mutex_init(&_cond_locker, NULL); 189 | pthread_cond_init(&_cond_var, NULL); 190 | #endif 191 | } 192 | 193 | ~ Event(){ 194 | release(); 195 | } 196 | 197 | void set( bool isSignal = true ){ 198 | if (isSignal){ 199 | #ifdef _WIN32 200 | SetEvent(_event); 201 | #else 202 | pthread_mutex_lock(&_cond_locker); 203 | 204 | if ( _is_signalled == false ){ 205 | _is_signalled = true; 206 | pthread_cond_signal(&_cond_var); 207 | } 208 | pthread_mutex_unlock(&_cond_locker); 209 | #endif 210 | }else{ 211 | #ifdef _WIN32 212 | ResetEvent(_event); 213 | #else 214 | pthread_mutex_lock(&_cond_locker); 215 | _is_signalled = false; 216 | pthread_mutex_unlock(&_cond_locker); 217 | #endif 218 | } 219 | } 220 | 221 | unsigned long wait( unsigned long timeout = 0xFFFFFFFF ){ 222 | #ifdef _WIN32 223 | switch (WaitForSingleObject(_event, timeout==0xFFFFFFF?INFINITE:(DWORD)timeout)){ 224 | case WAIT_FAILED: 225 | return EVENT_FAILED; 226 | case WAIT_OBJECT_0: 227 | return EVENT_OK; 228 | case WAIT_TIMEOUT: 229 | return EVENT_TIMEOUT; 230 | } 231 | return EVENT_OK; 232 | #else 233 | unsigned long ans = EVENT_OK; 234 | pthread_mutex_lock( &_cond_locker ); 235 | 236 | if (!_is_signalled){ 237 | if (timeout == 0xFFFFFFFF){ 238 | pthread_cond_wait(&_cond_var,&_cond_locker); 239 | }else{ 240 | timespec wait_time; 241 | timeval now; 242 | gettimeofday(&now,NULL); 243 | 244 | wait_time.tv_sec = timeout/1000 + now.tv_sec; 245 | wait_time.tv_nsec = (timeout%1000)*1000000ULL + now.tv_usec*1000; 246 | 247 | if (wait_time.tv_nsec >= 1000000000){ 248 | ++wait_time.tv_sec; 249 | wait_time.tv_nsec -= 1000000000; 250 | } 251 | switch (pthread_cond_timedwait(&_cond_var,&_cond_locker,&wait_time)){ 252 | case 0: 253 | // signalled 254 | break; 255 | case ETIMEDOUT: 256 | // time up 257 | ans = EVENT_TIMEOUT; 258 | goto _final; 259 | break; 260 | default: 261 | ans = EVENT_FAILED; 262 | goto _final; 263 | } 264 | 265 | } 266 | } 267 | 268 | assert(_is_signalled); 269 | 270 | if (_isAutoReset){ 271 | _is_signalled = false; 272 | } 273 | _final: 274 | pthread_mutex_unlock( &_cond_locker ); 275 | 276 | return ans; 277 | #endif 278 | 279 | } 280 | protected: 281 | 282 | void release() { 283 | #ifdef _WIN32 284 | CloseHandle(_event); 285 | #else 286 | pthread_mutex_destroy(&_cond_locker); 287 | pthread_cond_destroy(&_cond_var); 288 | #endif 289 | } 290 | 291 | #ifdef _WIN32 292 | HANDLE _event; 293 | #else 294 | pthread_cond_t _cond_var; 295 | pthread_mutex_t _cond_locker; 296 | bool _is_signalled; 297 | bool _isAutoReset; 298 | #endif 299 | }; 300 | 301 | class ScopedLocker 302 | { 303 | public : 304 | explicit ScopedLocker(Locker &l): _binded(l) { 305 | _binded.lock(); 306 | } 307 | 308 | void forceUnlock() { 309 | _binded.unlock(); 310 | } 311 | ~ScopedLocker() { 312 | _binded.unlock(); 313 | } 314 | Locker & _binded; 315 | }; 316 | 317 | 318 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/thread.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "Utils.h" 3 | 4 | #ifdef _WIN32 5 | #include 6 | #include 7 | #include 8 | #include 9 | #else 10 | #include 11 | #include 12 | #endif 13 | 14 | #define UNUSED(x) (void)x 15 | 16 | #if defined(__ANDROID__) 17 | #define pthread_cancel(x) 0 18 | #endif 19 | 20 | #define CLASS_THREAD(c , x ) Thread::ThreadCreateObjectFunctor(this) 21 | 22 | class Thread 23 | { 24 | public: 25 | 26 | template static Thread ThreadCreateObjectFunctor(CLASS * pthis){ 27 | return createThread(createThreadAux, pthis); 28 | } 29 | 30 | template static _size_t THREAD_PROC createThreadAux(void * param){ 31 | return (static_cast(param)->*PROC)(); 32 | } 33 | 34 | static Thread createThread(thread_proc_t proc, void * param = NULL ){ 35 | Thread thread_(proc, param); 36 | #if defined(_WIN32) 37 | thread_._handle = (_size_t)( _beginthreadex(NULL, 0, (unsigned int (__stdcall * )( void * ))proc, param, 0, NULL)); 38 | #else 39 | assert( sizeof(thread_._handle) >= sizeof(pthread_t)); 40 | 41 | pthread_create((pthread_t *)&thread_._handle, NULL, (void * (*)(void *))proc, param); 42 | #endif 43 | return thread_; 44 | } 45 | 46 | public: 47 | explicit Thread(): _param(NULL),_func(NULL),_handle(0){} 48 | virtual ~Thread(){} 49 | _size_t getHandle(){ 50 | return _handle; 51 | } 52 | int terminate(){ 53 | #if defined(_WIN32) 54 | if (!this->_handle){ 55 | return 0; 56 | } 57 | if (TerminateThread( reinterpret_cast(this->_handle), -1)){ 58 | CloseHandle(reinterpret_cast(this->_handle)); 59 | this->_handle = NULL; 60 | return 0; 61 | }else{ 62 | return -2; 63 | } 64 | 65 | #else 66 | if (!this->_handle) return 0; 67 | 68 | return pthread_cancel((pthread_t)this->_handle); 69 | #endif 70 | } 71 | void *getParam() { 72 | return _param; 73 | } 74 | int join(unsigned long timeout = -1){ 75 | if (!this->_handle){ 76 | return 0; 77 | } 78 | #if defined(_WIN32) 79 | switch ( WaitForSingleObject(reinterpret_cast(this->_handle), timeout)){ 80 | case WAIT_OBJECT_0: 81 | CloseHandle(reinterpret_cast(this->_handle)); 82 | this->_handle = NULL; 83 | return 0; 84 | case WAIT_ABANDONED: 85 | return -2; 86 | case WAIT_TIMEOUT: 87 | return -1; 88 | } 89 | #else 90 | UNUSED(timeout); 91 | pthread_join((pthread_t)(this->_handle), NULL); 92 | #endif 93 | return 0; 94 | } 95 | 96 | bool operator== ( const Thread & right) { 97 | return this->_handle == right._handle; 98 | } 99 | protected: 100 | explicit Thread( thread_proc_t proc, void * param ):_param(param),_func(proc), _handle(0){} 101 | void * _param; 102 | thread_proc_t _func; 103 | _size_t _handle; 104 | }; 105 | 106 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/timer.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file timer.h * 8 | * @brief time * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | #include 29 | #include 30 | #include 31 | #include 32 | 33 | 34 | 35 | #define BEGIN_STATIC_CODE( _blockname_ ) \ 36 | static class _static_code_##_blockname_ { \ 37 | public: \ 38 | _static_code_##_blockname_ () 39 | 40 | 41 | #define END_STATIC_CODE( _blockname_ ) \ 42 | } _instance_##_blockname_; 43 | 44 | 45 | #if defined(_WIN32) 46 | #include 47 | #define delay(x) ::Sleep(x) 48 | #else 49 | #include 50 | #include 51 | 52 | static inline void delay(uint32_t ms){ 53 | while (ms>=1000){ 54 | usleep(1000*1000); 55 | ms-=1000; 56 | }; 57 | if (ms!=0){ 58 | usleep(ms*1000); 59 | } 60 | } 61 | #endif 62 | 63 | 64 | namespace impl{ 65 | 66 | #if defined(_WIN32) 67 | void HPtimer_reset(); 68 | #endif 69 | uint32_t getHDTimer(); 70 | uint64_t getCurrentTime(); 71 | } 72 | 73 | 74 | #define getms() impl::getHDTimer() 75 | #define getTime() impl::getCurrentTime() 76 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/unix_timer.cpp: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file unix_timer.cpp * 8 | * @brief time * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #if !defined(_WIN32) 28 | #include "timer.h" 29 | 30 | namespace impl{ 31 | uint32_t getHDTimer() { 32 | struct timespec t; 33 | t.tv_sec = t.tv_nsec = 0; 34 | clock_gettime(CLOCK_MONOTONIC, &t); 35 | return t.tv_sec*1000L + t.tv_nsec/1000000L; 36 | } 37 | uint64_t getCurrentTime() 38 | { 39 | #if HAS_CLOCK_GETTIME 40 | struct timespec tim; 41 | clock_gettime(CLOCK_REALTIME, &tim); 42 | return (uint64_t)(tim.tv_sec*1000000000LL + tim.tv_nsec); 43 | #else 44 | struct timeval timeofday; 45 | gettimeofday(&timeofday,NULL); 46 | return (uint64_t)( timeofday.tv_sec*1000000000LL + timeofday.tv_usec * 1000); 47 | #endif 48 | } 49 | } 50 | #endif 51 | -------------------------------------------------------------------------------- /Lidar/Drivers/YDLidar/win_timer.cpp: -------------------------------------------------------------------------------- 1 | #if defined(_WIN32) 2 | #include "timer.h" 3 | #include 4 | #pragma comment(lib, "Winmm.lib") 5 | 6 | namespace impl{ 7 | 8 | static LARGE_INTEGER _current_freq; 9 | 10 | void HPtimer_reset() { 11 | BOOL ans=QueryPerformanceFrequency(&_current_freq); 12 | _current_freq.QuadPart/=1000; 13 | } 14 | 15 | uint32_t getHDTimer() { 16 | LARGE_INTEGER current; 17 | QueryPerformanceCounter(¤t); 18 | 19 | return (uint32_t)(current.QuadPart/(_current_freq.QuadPart)); 20 | } 21 | 22 | uint64_t getCurrentTime(){ 23 | FILETIME t; 24 | GetSystemTimeAsFileTime(&t); 25 | return ((((uint64_t)t.dwHighDateTime) << 32) | ((uint64_t)t.dwLowDateTime))*100; 26 | } 27 | 28 | 29 | BEGIN_STATIC_CODE(timer_cailb) { 30 | HPtimer_reset(); 31 | }END_STATIC_CODE(timer_cailb) 32 | 33 | } 34 | #endif 35 | -------------------------------------------------------------------------------- /Lidar/LIDARDevice.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file LIDARDevice.h * 8 | * @brief LIDAR Device Interface * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #include 30 | #include "LIDARDriverInterface.h" 31 | #include "Drivers/YDLidar/ydlidar_driver.h" 32 | #include "Drivers/YDLidar/timer.h" 33 | #include "DeviceException.h" 34 | 35 | namespace ydlidar { 36 | 37 | /////////////////////////////////////////////////////////////////////////////// 38 | // Generic LIDAR device 39 | class LIDAR : public LIDARDriverInterface 40 | { 41 | public: 42 | /////////////////////////////////////////////////////////////// 43 | LIDAR() { 44 | YDlidarDriver* pDriver = new YDlidarDriver; 45 | m_LIDAR = std::shared_ptr( pDriver ); 46 | } 47 | 48 | /////////////////////////////////////////////////////////////// 49 | ~LIDAR() { 50 | Clear(); 51 | } 52 | 53 | /////////////////////////////////////////////////////////////// 54 | void Clear() { 55 | m_LIDAR = nullptr; 56 | } 57 | 58 | ////////////////////////////////////////////////////////////// 59 | /** 60 | * @brief get current lidar lists 61 | * @return current online lidar list 62 | */ 63 | std::vector getLidarList() { 64 | if(m_LIDAR) { 65 | return m_LIDAR->getLidarList(); 66 | } else { 67 | throw DeviceException("error: no driver initialized!"); 68 | } 69 | } 70 | ////////////////////////////////////////////////////////////// 71 | /// \brief Update lidar configuration parameters 72 | /// \param configuration parameters 73 | /// 74 | void UpdateLidarParamCfg(const LaserParamCfg& config_msg) { 75 | if(m_LIDAR) { 76 | m_LIDAR->UpdateLidarParamCfg(config_msg); 77 | } else { 78 | throw DeviceException("error: no driver initialized!"); 79 | } 80 | } 81 | 82 | 83 | /////////////////////////////////////////////////////////////// 84 | /// \brief Registered lidar data callback 85 | /// \param callback function 86 | /// 87 | void RegisterLIDARDataCallback(LIDARDriverDataCallback callback) { 88 | if( m_LIDAR ) { 89 | m_LIDAR->RegisterLIDARDataCallback( callback ); 90 | } else { 91 | throw DeviceException("error: no driver initialized!"); 92 | } 93 | } 94 | /////////////////////////////////////////////////////////////// 95 | /// \brief continuous access to lidar data 96 | /// 97 | void spinOnce() { 98 | if( m_LIDAR ) { 99 | m_LIDAR->spinOnce(); 100 | } else { 101 | throw DeviceException("error: no driver initialized!"); 102 | } 103 | } 104 | 105 | 106 | protected: 107 | std::shared_ptr m_LIDAR; 108 | 109 | }; 110 | 111 | } /* namespace */ 112 | -------------------------------------------------------------------------------- /Lidar/LIDARDriverInterface.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file LIDARDriverInterface.h * 8 | * @brief LIDAR Interface * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #include 30 | #include 31 | #include "Utils.h" 32 | 33 | 34 | namespace ydlidar { 35 | 36 | typedef std::function LIDARDriverDataCallback; 37 | 38 | /////////////////////////////////////////////////////////////////////////////// 39 | /// Generic LIDAR driver interface 40 | class LIDARDriverInterface 41 | { 42 | public: 43 | // Pure virtual functions driver writers must implement: 44 | virtual ~LIDARDriverInterface() {} 45 | 46 | 47 | /** 48 | * @brief get current lidar list 49 | * @return current online lidar list 50 | */ 51 | virtual std::vector getLidarList() = 0; 52 | /** 53 | * @brief Update lidar configuration parameters 54 | * @param configuration parameters 55 | */ 56 | virtual void UpdateLidarParamCfg(const LaserParamCfg& config_msg) = 0; 57 | 58 | /** 59 | * @brief Registered lidar data callback 60 | * @param data callback function 61 | */ 62 | virtual void RegisterLIDARDataCallback(LIDARDriverDataCallback callback) = 0; 63 | 64 | /** 65 | * @brief continuous access to lidar data 66 | */ 67 | virtual void spinOnce() = 0; 68 | 69 | }; 70 | 71 | } /* namespace */ 72 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | 2 | ![YDLIDAR](image/index-X4.jpg "YDLIDAR_X4") 3 | 4 | YDLIDAR SDK [![Build Status](https://travis-ci.org/cansik/ydlidar_sdk.svg?branch=master)](https://travis-ci.org/cansik/ydlidar_sdk) [![Build status](https://ci.appveyor.com/api/projects/status/2w9xm1dbafbi7xc0?svg=true)](https://ci.appveyor.com/project/cansik/ydlidar_sdk) [![codebeat badge](https://codebeat.co/badges/3d8634b7-84eb-410c-b92b-24bf6875d8ef)](https://codebeat.co/projects/github-com-cansik-ydlidar_sdk-master) 5 | ===================================================================== 6 | 7 | 8 | Introduction 9 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 10 | 11 | YDLIDAR(https://www.ydlidar.com/) series is a set of high-performance and low-cost LIDAR sensors, which is the perfect sensor of 2D SLAM, 3D reconstruction, multi-touch, and safety applications. 12 | 13 | If you are using ROS (Robot Operating System), please use our open-source [ROS Driver]( https://github.com/yangfuyuan/ydlidar_ros) . 14 | 15 | Release Notes 16 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 17 | | Title | Version | Data | 18 | | :-------- | --------:| :--: | 19 | | SDK | 1.3.8 | 2018-11-13 | 20 | 21 | 22 | - [new feature] output scan frequency. 23 | - [new feature] repair Device health exception. 24 | 25 | 26 | 27 | Dataset 28 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 29 | 30 | Support LIDAR Model(Only S4Pro support intensity) 31 | 32 | 33 | | Model | Baudrate | Sampling Frequency | Range(m) | Scanning Frequency(HZ) | Working temperature(°C) | Laser power max(mW) | voltage(V) | Current(mA) 34 | | :-------- | --------:|--------:| --------:| --------:|--------:| --------:| --------:| :--: | 35 | | G4 | 230400 | 9000 | 0.26-16 |5-12|0-50| ~5|4.8-5.2|400-480| 36 | | X4 | 128000 | 5000 | 0.12-10 |5-12|0-40| ~5|4.8-5.2|330-380| 37 | | F4 | 115200 | 4000 | 0.1-12 |5-12|0-40| ~5|4.8-5.2|400-480| 38 | | S4 | 115200| 4000 | 0.1-8 |6-12|0-40| ~5|4.8-5.2|330-380| 39 | | S4Pro | 153600| 4000 | 0.1-8 |6-12|0-40| ~5|4.8-5.2|330-380| 40 | 41 | How to build YDLIDAR SDK samples 42 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 43 | 44 | $ git clone https://github.com/yangfuyuan/ydlidar_sdk 45 | 46 | $ cd ydlidar_sdk 47 | 48 | $ git checkout master 49 | 50 | 51 | Linux: 52 | 53 | $ cd startup 54 | 55 | $ chmod +x initenv.sh 56 | 57 | $ sudo ./initenv.sh ##change the serial port to be readable and writable 58 | 59 | $ cd ../.. 60 | 61 | $ mkdir build 62 | 63 | $ cd build 64 | 65 | $ cmake ../ydlidar_sdk ##windows: cmake -G "Visual Studio 14 2017 Win64" ../ydlidar_sdk 66 | 67 | $ make 68 | 69 | 70 | 71 | Windows: 72 | 73 | 1. install [cmake](https://cmake.org/download/)(if there is no cmake) 74 | 75 | 76 | 2. build steps: 77 | 78 | 79 | Step1: open cmake-gui and select source code/binaries directory 80 | 81 | 82 | ![YDLIDAR](image/step1.png "YDLIDAR") 83 | 84 | 85 | Step2: Configure and select build toolchain(choose the VS version in your system) 86 | 87 | 88 | ![YDLIDAR](image/step2.png "YDLIDAR") 89 | 90 | 91 | Step3: configuring done(click "Configure" button) 92 | 93 | 94 | ![YDLIDAR](image/step3.png "YDLIDAR") 95 | 96 | 97 | Step4: generating done(click "Generate" button) 98 | 99 | 100 | ![YDLIDAR](image/step4.png "YDLIDAR") 101 | 102 | 103 | Step5: open vs Project in binaries directory 104 | 105 | 106 | ![YDLIDAR](image/step5.png "YDLIDAR") 107 | 108 | 109 | Step6: build finished and run test: 110 | 111 | 112 | ![YDLIDAR](image/step6.png "YDLIDAR") 113 | 114 | 115 | 3. Compile wth Qt: 116 | 1). Qt configuration cmake 117 | 2). Open the CmakeLists.txt project file with Qt. 118 | 119 | 120 | 121 | 122 | How to run YDLIDAR SDK samples 123 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 124 | 125 | linux: 126 | 127 | $ ./ydlidar_test 128 | 129 | YDLIDAR C++ TEST 130 | 131 | Radar[ydlidar7] detected, whether to select current radar(yes/no)?:yes 132 | 133 | 0. ydlidar7 134 | 135 | $ Please select the lidar port:0 136 | 137 | 0. 115200 138 | 139 | 1. 128000 140 | 141 | 2. 153600 142 | 143 | 3. 230400 144 | 145 | $ Please select the lidar baud rate:3 146 | 147 | 0. false 148 | 149 | 1. true 150 | 151 | $ Please select the lidar intensity:0 152 | 153 | 154 | windows: 155 | 156 | $ ydlidar_test.exe 157 | 158 | YDLIDAR C++ TEST 159 | 160 | Radar[ydlidar7] detected, whether to select current radar(yes/no)?:yes 161 | 162 | 0. ydlidar7 163 | 164 | $ Please select the lidar port:0 165 | 166 | 0. 115200 167 | 168 | 1. 128000 169 | 170 | 2. 153600 171 | 172 | 3. 230400 173 | 174 | $ Please select the lidar baud rate:3 175 | 176 | 0. false 177 | 178 | 1. true 179 | 180 | $ Please select the lidar intensity:0 181 | 182 | 183 | Console Display: 184 | 185 | You should see YDLIDAR's scan result in the console: 186 | 187 | YDLIDAR C++ TEST 188 | 189 | Radar[ydlidar7] detected, whether to select current radar(yes/no)?:yes 190 | 191 | 0. ydlidar7 192 | 193 | Please select the lidar port:0 194 | 195 | 0. 115200 196 | 197 | 1. 128000 198 | 199 | 2. 153600 200 | 201 | 3. 230400 202 | 203 | Please select the lidar baud rate:3 204 | 205 | 0. false 206 | 207 | 1. true 208 | 209 | Please select the lidar intensity:0 210 | 211 | SDK Version: 1..3.8 212 | 213 | LIDAR Version: 1.3.8 214 | 215 | fhs_lock: creating lockfile: 18341 216 | 217 | firmware: 521 218 | 219 | [YDLIDAR] Connection established in [/dev/ttyUSB0]: 220 | 221 | Firmware version: 2.0.9 222 | 223 | Hardware version: 2 224 | 225 | Model: G4 226 | 227 | Serial: 2018042100000023 228 | 229 | [YDLIDAR INFO] Current Sampling Rate : 9K 230 | 231 | [YDLIDAR INFO] Current Scan Frequency : 7.000000Hz 232 | 233 | received scan size: 1039 234 | 235 | scan system time: 1534400129245291000 236 | 237 | scan self time: 1534400129103710800 238 | 239 | scan frequency: 8.67053HZ 240 | 241 | received scan size: 1231 242 | 243 | scan system time: 1534400129379541000 244 | 245 | scan self time: 1534400129232496800 246 | 247 | scan frequency: 7.31708HZ 248 | 249 | received scan size: 1272 250 | 251 | scan system time: 1534400129530262000 252 | 253 | scan self time: 1534400129378863800 254 | 255 | scan frequency: 7.08105HZ 256 | 257 | received scan size: 1295 258 | 259 | scan system time: 1534400129671749000 260 | 261 | scan self time: 1534400129519748800 262 | 263 | scan frequency: 6.95518HZ 264 | 265 | ^Csignal_handler(2) 266 | 267 | received scan size: 1341 268 | 269 | scan system time: 1534400129839365000 270 | 271 | scan self time: 1534400129671106800 272 | 273 | scan frequency: 6.71642HZ 274 | 275 | fhs_unlock: Removing LockFile 276 | 277 | 278 | Note: If you have already run the program once. change the configuration parameters through the "lidar.ini" file. 279 | 280 | Data structure 281 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 282 | 283 | data structure: 284 | 285 | //! A struct for returning configuration from the YDLIDAR 286 | struct LaserConfig { 287 | 288 | //! Start angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top. 289 | float min_angle; 290 | 291 | //! Stop angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top. 292 | float max_angle; 293 | 294 | //! Scan resolution [rad]. 295 | float ang_increment; 296 | 297 | //! Scan resoltuion [ns] 298 | float time_increment; 299 | 300 | //! Time between scans 301 | float scan_time; 302 | 303 | //! Minimum range [m] 304 | float min_range; 305 | 306 | //! Maximum range [m] 307 | float max_range; 308 | 309 | //! Range Resolution [m] 310 | float range_res; 311 | 312 | }; 313 | 314 | 315 | struct LaserScan { 316 | 317 | //! Array of ranges 318 | std::vector ranges; 319 | 320 | //! Array of intensities 321 | std::vector intensities; 322 | 323 | //! Self reported time stamp in nanoseconds 324 | uint64_t self_time_stamp; 325 | 326 | //! System time when first range was measured in nanoseconds 327 | uint64_t system_time_stamp; 328 | 329 | //! Configuration of scan 330 | LaserConfig config; 331 | 332 | ///lidar scan frequency 333 | float scan_frequency; 334 | 335 | }; 336 | 337 | example angle parsing: 338 | 339 | for(size_t i =0; i < scan.ranges.size(); i++) { 340 | 341 | // current angle 342 | double angle = scan.config.min_angle + i*scan.config.ang_increment;// radian format 343 | 344 | //current distance 345 | double distance = scan.ranges[i];//meters 346 | 347 | //current intensity 348 | int intensity = scan.intensities[i]; 349 | 350 | } 351 | 352 | laser callback function code : 353 | 354 | void LaserScanCallback(const LaserScan& scan) { 355 | 356 | std::cout<< "received scan size: "<< scan.ranges.size()< ports = YDlidarDriver::lidarPortList(); 454 | 455 | for(std::vector::iterator it = ports.begin(); it != ports.end(); it++) { 456 | 457 | printf("%s\n", (*it).c_str()); 458 | 459 | } 460 | 461 | ``` 462 | 463 | 464 | Coordinate System 465 | ------------------------------------------------------------------------------------------------------------------------------------------------------- 466 | 467 | ![Coordinate](image/image.png "Coordinate") 468 | 469 | 470 | 471 | ### The relationship between the angle value and the data structure in the above figure: 472 | 473 | double current_angle = scan.config.min_angle + index*scan.config.ang_increment;// radian format 474 | doube Angle = current_angle*180/M_PI;//Angle fomat 475 | 476 | 477 | Contact EAI 478 | --------------- 479 | 480 | If you have any extra questions, please feel free to [contact us](http://www.ydlidar.cn/cn/contact) 481 | 482 | -------------------------------------------------------------------------------- /Samples/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | cmake_minimum_required(VERSION 2.8) 3 | PROJECT(ydlidar_test) 4 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 5 | add_definitions(-std=c++11) # Use C++11 6 | 7 | set (CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}) 8 | 9 | #Include directories 10 | INCLUDE_DIRECTORIES( 11 | ${CMAKE_SOURCE_DIR} 12 | ${CMAKE_BINARY_DIR} 13 | ${CMAKE_SOURCE_DIR}/../ 14 | ${CMAKE_CURRENT_BINARY_DIR} 15 | ) 16 | 17 | 18 | LINK_DIRECTORIES(${CMAKE_BINARY_DIR}) 19 | ADD_EXECUTABLE(${PROJECT_NAME} 20 | test.cpp) 21 | ADD_EXECUTABLE(${PROJECT_NAME}1 22 | test1.cpp) 23 | 24 | # Add the required libraries for linking: 25 | TARGET_LINK_LIBRARIES(${PROJECT_NAME} ydlidar_driver) 26 | TARGET_LINK_LIBRARIES(${PROJECT_NAME}1 ydlidar_driver) 27 | 28 | -------------------------------------------------------------------------------- /Samples/lidar.ini: -------------------------------------------------------------------------------- 1 | [LIDAR] 2 | serialPort = /dev/ttyUSB0 3 | serialBaudrate = 230400 4 | sampleRate = 9 5 | scanFrequency = 7 6 | intensity = false 7 | autoReconnect = true 8 | exposure = false 9 | fixedResolution = false 10 | reversion = false 11 | heartBeat = false 12 | maxAngle = 180.000000 13 | minAngle = -180.000000 14 | maxRange = 16.000000 15 | minRange = 0.100000 16 | -------------------------------------------------------------------------------- /Samples/test.cpp: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file test.cpp * 8 | * @brief Lidar test * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | 28 | #ifdef _WIN32 29 | # pragma warning(disable: 4786) 30 | #pragma comment(lib, "ydlidar_driver.lib") 31 | #endif 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | 39 | using namespace std; 40 | using namespace ydlidar; 41 | 42 | std::vector split(const std::string &s, char delim) { 43 | std::vector elems; 44 | std::stringstream ss(s); 45 | std::string number; 46 | while(std::getline(ss, number, delim)) { 47 | elems.push_back(atof(number.c_str())); 48 | } 49 | return elems; 50 | } 51 | 52 | 53 | void LaserScanCallback(const LaserScan& scan) { 54 | 55 | std::cout<< "received scan size: "<< scan.ranges.size()< 1) { 92 | if(argc > 1) 93 | ini_file = (std::string)argv[1]; 94 | if(fileExists(ini_file.c_str())) { 95 | SI_Error rc = ini.LoadFile(ini_file.c_str()); 96 | if(rc >= 0 ) { 97 | input = false; 98 | const char * pszValue = ini.GetValue("LIDAR", "serialPort", ""); 99 | cfg.serialPort = pszValue; 100 | if(cfg.serialPort.empty()) { 101 | input = true; 102 | } 103 | 104 | pszValue = ini.GetValue("LIDAR", "ignoreArray", ""); 105 | 106 | cfg.ignoreArray = split(pszValue,','); 107 | 108 | cfg.serialBaudrate = ini.GetLongValue("LIDAR", "serialBaudrate", cfg.serialBaudrate); 109 | cfg.sampleRate = ini.GetLongValue("LIDAR", "sampleRate", cfg.sampleRate); 110 | cfg.scanFrequency = ini.GetLongValue("LIDAR", "scanFrequency", cfg.scanFrequency); 111 | 112 | cfg.intensity = ini.GetBoolValue("LIDAR", "intensity", cfg.intensity); 113 | cfg.autoReconnect = ini.GetBoolValue("LIDAR", "autoReconnect", cfg.autoReconnect); 114 | cfg.exposure = ini.GetBoolValue("LIDAR", "exposure", cfg.exposure); 115 | cfg.fixedResolution = ini.GetBoolValue("LIDAR", "fixedResolution", cfg.fixedResolution); 116 | cfg.reversion = ini.GetBoolValue("LIDAR", "reversion", cfg.reversion); 117 | cfg.heartBeat = ini.GetBoolValue("LIDAR", "heartBeat", cfg.heartBeat); 118 | 119 | cfg.maxAngle = ini.GetDoubleValue("LIDAR", "maxAngle", cfg.maxAngle); 120 | cfg.minAngle = ini.GetDoubleValue("LIDAR", "minAngle", cfg.minAngle); 121 | cfg.maxRange = ini.GetDoubleValue("LIDAR", "maxRange", cfg.maxRange); 122 | cfg.minRange = ini.GetDoubleValue("LIDAR", "minRange", cfg.minRange); 123 | } 124 | } 125 | 126 | } 127 | 128 | 129 | 130 | bool excep = false; 131 | bool input_port =false; 132 | try { 133 | LIDAR ydlidar; 134 | std::vector ports = ydlidar.getLidarList(); 135 | if(ports.size() == 1) { 136 | if(cfg.serialPort != ports[0]) { 137 | std::string str; 138 | printf("Radar[%s] detected, whether to select current radar(yes/no)?:", ports[0].c_str()); 139 | std::cin>>str; 140 | for (size_t i=0; i >port; 159 | cfg.serialPort = port; 160 | input_port = true; 161 | } 162 | 163 | 164 | if(!input_port) { 165 | 166 | int size = 0; 167 | for(std::vector::iterator it = ports.begin(); it != ports.end(); it++) { 168 | printf("%d. %s\n", size, (*it).c_str()); 169 | size++; 170 | } 171 | 172 | 173 | select_port: 174 | printf("Please select the lidar port:"); 175 | std::cin>>port; 176 | if((size_t)atoi(port.c_str()) >= ports.size()) { 177 | printf("Invalid serial number, Please re-select\n"); 178 | goto select_port; 179 | } 180 | cfg.serialPort = ports[atoi(port.c_str())]; 181 | 182 | } 183 | 184 | 185 | 186 | std::vector baud; 187 | baud.push_back(115200); 188 | baud.push_back(128000); 189 | baud.push_back(153600); 190 | baud.push_back(230400); 191 | 192 | for( unsigned int i = 0; i < baud.size(); i ++) { 193 | printf("%u. %u\n", i, baud[i]); 194 | } 195 | 196 | select_baud: 197 | printf("Please select the lidar baud rate:"); 198 | std::cin>>baudrate; 199 | 200 | if(atoi(baudrate.c_str()) >= 4) { 201 | printf("Invalid serial number, Please re-select\n"); 202 | goto select_baud; 203 | 204 | } 205 | cfg.serialBaudrate = baud[atoi(baudrate.c_str())]; 206 | 207 | 208 | printf("0. false\n"); 209 | printf("1. true\n"); 210 | select_intensity: 211 | printf("Please select the lidar intensity:"); 212 | std::cin>>intensity; 213 | 214 | if(atoi(intensity.c_str()) >= 2) { 215 | printf("Invalid serial number, Please re-select\n"); 216 | goto select_intensity; 217 | 218 | } 219 | cfg.intensity = atoi(intensity.c_str()) ==0?false:true; 220 | } 221 | 222 | ini.SetValue("LIDAR", "serialPort", cfg.serialPort.c_str()); 223 | 224 | ini.SetLongValue("LIDAR", "serialBaudrate", cfg.serialBaudrate); 225 | ini.SetLongValue("LIDAR", "sampleRate", cfg.sampleRate); 226 | ini.SetLongValue("LIDAR", "scanFrequency", cfg.scanFrequency); 227 | 228 | 229 | ini.SetBoolValue("LIDAR", "intensity", cfg.intensity); 230 | ini.SetBoolValue("LIDAR", "autoReconnect", cfg.autoReconnect); 231 | ini.SetBoolValue("LIDAR", "exposure", cfg.exposure); 232 | ini.SetBoolValue("LIDAR", "fixedResolution", cfg.fixedResolution); 233 | ini.SetBoolValue("LIDAR", "reversion", cfg.reversion); 234 | ini.SetBoolValue("LIDAR", "heartBeat", cfg.heartBeat); 235 | 236 | ini.SetDoubleValue("LIDAR", "maxAngle", cfg.maxAngle); 237 | ini.SetDoubleValue("LIDAR", "minAngle", cfg.minAngle); 238 | ini.SetDoubleValue("LIDAR", "maxRange", cfg.maxRange); 239 | ini.SetDoubleValue("LIDAR", "minRange", cfg.minRange); 240 | 241 | std::cout<<"SDK Version: "<< SDK_VERSION< | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #ifdef _WIN32 28 | # pragma warning(disable: 4786) 29 | #pragma comment(lib, "ydlidar_driver.lib") 30 | #endif 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | 37 | #include 38 | #include 39 | #include 40 | 41 | 42 | using namespace std; 43 | using namespace ydlidar; 44 | 45 | class LidarTest 46 | { 47 | public: 48 | explicit LidarTest(const LaserParamCfg& config); 49 | ~LidarTest(); 50 | 51 | void run(); 52 | 53 | void LidarScanCallBack(const LaserScan &scan); 54 | 55 | private: 56 | LaserParamCfg m_config; 57 | std::shared_ptr m_lidar; 58 | }; 59 | 60 | LidarTest::LidarTest(const LaserParamCfg& config) : 61 | m_config(config){ 62 | m_lidar.reset(new ydlidar::LIDAR); 63 | } 64 | 65 | LidarTest::~LidarTest() { 66 | m_lidar.reset(); 67 | } 68 | 69 | void LidarTest::LidarScanCallBack(const LaserScan &scan) { 70 | std::cout<< "received scan size: "<< scan.ranges.size()<UpdateLidarParamCfg(m_config); 97 | 98 | m_lidar->RegisterLIDARDataCallback(std::bind(&LidarTest::LidarScanCallBack, this, std::placeholders::_1)); 99 | 100 | 101 | while (ydlidar::ok()) { 102 | 103 | try { 104 | m_lidar->spinOnce(); 105 | }catch(TimeoutException& e) { 106 | std::cout<< e.what()< split(const std::string &s, char delim) { 136 | std::vector elems; 137 | std::stringstream ss(s); 138 | std::string number; 139 | while(std::getline(ss, number, delim)) { 140 | elems.push_back(atof(number.c_str())); 141 | } 142 | return elems; 143 | } 144 | 145 | int main(int argc, char **argv) { 146 | printf(" YDLIDAR C++ TEST\n"); 147 | 148 | ydlidar::init(argc, argv); 149 | CSimpleIniA ini; 150 | ini.SetUnicode(); 151 | LaserParamCfg cfg; 152 | bool input = true; 153 | std::string ini_file = "lidar.ini"; 154 | bool ini_exist = fileExists(ini_file.c_str()); 155 | if(ini_exist || argc > 1) { 156 | if(argc > 1) 157 | ini_file = (std::string)argv[1]; 158 | if(fileExists(ini_file.c_str())) { 159 | SI_Error rc = ini.LoadFile(ini_file.c_str()); 160 | if(rc >= 0 ) { 161 | input = false; 162 | const char * pszValue = ini.GetValue("LIDAR", "serialPort", ""); 163 | cfg.serialPort = pszValue; 164 | 165 | pszValue = ini.GetValue("LIDAR", "ignoreArray", ""); 166 | 167 | cfg.ignoreArray = split(pszValue,','); 168 | 169 | cfg.serialBaudrate = ini.GetLongValue("LIDAR", "serialBaudrate", cfg.serialBaudrate); 170 | cfg.sampleRate = ini.GetLongValue("LIDAR", "sampleRate", cfg.sampleRate); 171 | cfg.scanFrequency = ini.GetLongValue("LIDAR", "scanFrequency", cfg.scanFrequency); 172 | 173 | cfg.intensity = ini.GetBoolValue("LIDAR", "intensity", cfg.intensity); 174 | cfg.autoReconnect = ini.GetBoolValue("LIDAR", "autoReconnect", cfg.autoReconnect); 175 | cfg.exposure = ini.GetBoolValue("LIDAR", "exposure", cfg.exposure); 176 | cfg.fixedResolution = ini.GetBoolValue("LIDAR", "fixedResolution", cfg.fixedResolution); 177 | cfg.reversion = ini.GetBoolValue("LIDAR", "reversion", cfg.reversion); 178 | cfg.heartBeat = ini.GetBoolValue("LIDAR", "heartBeat", cfg.heartBeat); 179 | 180 | cfg.maxAngle = ini.GetDoubleValue("LIDAR", "maxAngle", cfg.maxAngle); 181 | cfg.minAngle = ini.GetDoubleValue("LIDAR", "minAngle", cfg.minAngle); 182 | cfg.maxRange = ini.GetDoubleValue("LIDAR", "maxRange", cfg.maxRange); 183 | cfg.minRange = ini.GetDoubleValue("LIDAR", "minRange", cfg.minRange); 184 | } 185 | } 186 | 187 | } 188 | 189 | 190 | bool input_port = false; 191 | std::vector ports = YDlidarDriver::lidarPortList();; 192 | if(ports.size() == 1) { 193 | if(cfg.serialPort != ports[0]) { 194 | std::string str; 195 | printf("Radar[%s] detected, whether to select current radar(yes/no)?:", ports[0].c_str()); 196 | std::cin>>str; 197 | for (size_t i=0; i >port; 215 | cfg.serialPort = port; 216 | input_port = true; 217 | } 218 | 219 | if(!input_port) { 220 | int size = 0; 221 | for(std::vector::iterator it = ports.begin(); it != ports.end(); it++) { 222 | printf("%d. %s\n", size, (*it).c_str()); 223 | size++; 224 | } 225 | 226 | select_port: 227 | printf("Please select the lidar port:"); 228 | std::cin>>port; 229 | if((size_t)atoi(port.c_str()) >= ports.size()) { 230 | printf("Invalid serial number, Please re-select\n"); 231 | goto select_port; 232 | } 233 | cfg.serialPort = ports[atoi(port.c_str())]; 234 | 235 | } 236 | 237 | 238 | std::vector baud; 239 | baud.push_back(115200); 240 | baud.push_back(128000); 241 | baud.push_back(153600); 242 | baud.push_back(230400); 243 | 244 | for( unsigned int i = 0; i < baud.size(); i ++) { 245 | printf("%u. %u\n", i, baud[i]); 246 | } 247 | 248 | select_baud: 249 | printf("Please select the lidar baud rate:"); 250 | std::cin>>baudrate; 251 | 252 | if(atoi(baudrate.c_str()) >= 4) { 253 | printf("Invalid serial number, Please re-select\n"); 254 | goto select_baud; 255 | 256 | } 257 | cfg.serialBaudrate = baud[atoi(baudrate.c_str())]; 258 | 259 | 260 | printf("0. false\n"); 261 | printf("1. true\n"); 262 | select_intensity: 263 | printf("Please select the lidar intensity:"); 264 | std::cin>>intensity; 265 | 266 | if(atoi(intensity.c_str()) >= 2) { 267 | printf("Invalid serial number, Please re-select\n"); 268 | goto select_intensity; 269 | 270 | } 271 | cfg.intensity = atoi(intensity.c_str()) ==0?false:true; 272 | } 273 | 274 | ini.SetValue("LIDAR", "serialPort", cfg.serialPort.c_str()); 275 | 276 | ini.SetLongValue("LIDAR", "serialBaudrate", cfg.serialBaudrate); 277 | ini.SetLongValue("LIDAR", "sampleRate", cfg.sampleRate); 278 | ini.SetLongValue("LIDAR", "scanFrequency", cfg.scanFrequency); 279 | 280 | 281 | ini.SetBoolValue("LIDAR", "intensity", cfg.intensity); 282 | ini.SetBoolValue("LIDAR", "autoReconnect", cfg.autoReconnect); 283 | ini.SetBoolValue("LIDAR", "exposure", cfg.exposure); 284 | ini.SetBoolValue("LIDAR", "fixedResolution", cfg.fixedResolution); 285 | ini.SetBoolValue("LIDAR", "reversion", cfg.reversion); 286 | ini.SetBoolValue("LIDAR", "heartBeat", cfg.heartBeat); 287 | 288 | ini.SetDoubleValue("LIDAR", "maxAngle", cfg.maxAngle); 289 | ini.SetDoubleValue("LIDAR", "minAngle", cfg.minAngle); 290 | ini.SetDoubleValue("LIDAR", "maxRange", cfg.maxRange); 291 | ini.SetDoubleValue("LIDAR", "minRange", cfg.minRange); 292 | 293 | std::cout <<"SDK Version: "<< SDK_VERSION < | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR} ) 28 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/impl ) 29 | 30 | set(HDRS 31 | LIDARDevice.h 32 | LIDARDriverInterface.h 33 | Utils.h 34 | DeviceException.h 35 | ) 36 | 37 | list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}) 38 | add_to_hal_sources(serial.cpp ) 39 | add_to_hal_headers( common.h serial.h) 40 | 41 | IF (WIN32) 42 | add_to_hal_sources(impl/windows/win_serial.cpp impl/windows/list_ports_win.cpp) 43 | add_to_hal_headers(impl/windows/win.h impl/windows/win_serial.h) 44 | ELSE() 45 | add_to_hal_sources(impl/unix/unix_serial.cpp impl/unix/list_ports_linux.cpp lock.c ) 46 | add_to_hal_headers(impl/unix/unix.h impl/unix/unix_serial.h lock.h) 47 | ENDIF() 48 | 49 | 50 | 51 | -------------------------------------------------------------------------------- /Serial/common.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file common.h * 8 | * @brief help * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #if defined(_WIN32) 30 | #include "impl\windows\win.h" 31 | #include "impl\windows\win_serial.h" 32 | #elif defined(__GNUC__) 33 | #include "impl/unix/unix.h" 34 | #include "impl/unix/unix_serial.h" 35 | #include "lock.h" 36 | #else 37 | #error "unsupported target" 38 | #endif 39 | 40 | #include "serial.h" 41 | 42 | #define SDKVerision "1.3.7" 43 | -------------------------------------------------------------------------------- /Serial/impl/unix/list_ports_linux.cpp: -------------------------------------------------------------------------------- 1 | #if defined(__linux__) 2 | 3 | /* 4 | * Copyright (c) 2014 Craig Lilley 5 | * This software is made available under the terms of the MIT licence. 6 | * A copy of the licence can be obtained from: 7 | * http://opensource.org/licenses/MIT 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "serial.h" 27 | 28 | using serial::PortInfo; 29 | using std::istringstream; 30 | using std::ifstream; 31 | using std::getline; 32 | using std::vector; 33 | using std::string; 34 | using std::cout; 35 | using std::endl; 36 | 37 | static vector glob(const vector& patterns); 38 | static string basename(const string& path); 39 | static string dirname(const string& path); 40 | static bool path_exists(const string& path); 41 | static string realpath(const string& path); 42 | static string usb_sysfs_friendly_name(const string& sys_usb_path, string& device_id); 43 | static vector get_sysfs_info(const string& device_path); 44 | static string read_line(const string& file); 45 | static string usb_sysfs_hw_string(const string& sysfs_path); 46 | static string format(const char* format, ...); 47 | 48 | vector 49 | glob(const vector& patterns) 50 | { 51 | vector paths_found; 52 | 53 | if(patterns.size() == 0) 54 | return paths_found; 55 | 56 | glob_t glob_results; 57 | 58 | int glob_retval = glob(patterns[0].c_str(), 0, NULL, &glob_results); 59 | 60 | vector::const_iterator iter = patterns.begin(); 61 | 62 | while(++iter != patterns.end()) 63 | { 64 | glob_retval = glob(iter->c_str(), GLOB_APPEND, NULL, &glob_results); 65 | } 66 | 67 | for(int path_index = 0; path_index < glob_results.gl_pathc; path_index++) 68 | { 69 | paths_found.push_back(glob_results.gl_pathv[path_index]); 70 | } 71 | 72 | globfree(&glob_results); 73 | 74 | return paths_found; 75 | } 76 | 77 | string 78 | basename(const string& path) 79 | { 80 | size_t pos = path.rfind("/"); 81 | 82 | if(pos == std::string::npos) 83 | return path; 84 | 85 | return string(path, pos+1, string::npos); 86 | } 87 | 88 | string 89 | dirname(const string& path) 90 | { 91 | size_t pos = path.rfind("/"); 92 | 93 | if(pos == std::string::npos) 94 | return path; 95 | else if(pos == 0) 96 | return "/"; 97 | 98 | return string(path, 0, pos); 99 | } 100 | 101 | bool 102 | path_exists(const string& path) 103 | { 104 | struct stat sb; 105 | 106 | if( stat(path.c_str(), &sb ) == 0 ) 107 | return true; 108 | 109 | return false; 110 | } 111 | 112 | string 113 | realpath(const string& path) 114 | { 115 | char* real_path = realpath(path.c_str(), NULL); 116 | 117 | string result; 118 | 119 | if(real_path != NULL) 120 | { 121 | result = real_path; 122 | 123 | free(real_path); 124 | } 125 | 126 | return result; 127 | } 128 | 129 | string 130 | usb_sysfs_friendly_name(const string& sys_usb_path, string& device_id) 131 | { 132 | unsigned int device_number = 0; 133 | 134 | istringstream( read_line(sys_usb_path + "/devnum") ) >> device_number; 135 | 136 | string manufacturer = read_line( sys_usb_path + "/manufacturer" ); 137 | 138 | string product = read_line( sys_usb_path + "/product" ); 139 | 140 | string serial = read_line( sys_usb_path + "/serial" ); 141 | 142 | device_id = read_line( sys_usb_path + "/devpath" ); 143 | 144 | if( manufacturer.empty() && product.empty() && serial.empty()) 145 | return ""; 146 | 147 | return format("%s %s %s", manufacturer.c_str(), product.c_str(), serial.c_str()); 148 | } 149 | 150 | vector 151 | get_sysfs_info(const string& device_path) 152 | { 153 | string device_name = basename( device_path ); 154 | 155 | string friendly_name; 156 | 157 | string hardware_id; 158 | 159 | string device_id; 160 | 161 | string sys_device_path = format( "/sys/class/tty/%s/device", device_name.c_str() ); 162 | 163 | if( device_name.compare(0,6,"ttyUSB") == 0 ) 164 | { 165 | sys_device_path = dirname( dirname( realpath( sys_device_path ) ) ); 166 | 167 | if( path_exists( sys_device_path ) ) 168 | { 169 | friendly_name = usb_sysfs_friendly_name( sys_device_path, device_id ); 170 | 171 | hardware_id = usb_sysfs_hw_string( sys_device_path ); 172 | } 173 | } 174 | else if( device_name.compare(0,6,"ttyACM") == 0 ) 175 | { 176 | sys_device_path = dirname( realpath( sys_device_path ) ); 177 | 178 | if( path_exists( sys_device_path ) ) 179 | { 180 | friendly_name = usb_sysfs_friendly_name( sys_device_path, device_id ); 181 | 182 | hardware_id = usb_sysfs_hw_string( sys_device_path ); 183 | } 184 | } 185 | else 186 | { 187 | // Try to read ID string of PCI device 188 | 189 | string sys_id_path = sys_device_path + "/id"; 190 | 191 | if( path_exists( sys_id_path ) ) 192 | hardware_id = read_line( sys_id_path ); 193 | } 194 | 195 | if( friendly_name.empty() ) 196 | friendly_name = device_name; 197 | 198 | if( hardware_id.empty() ) 199 | hardware_id = "n/a"; 200 | 201 | vector result; 202 | result.push_back(friendly_name); 203 | result.push_back(hardware_id); 204 | result.push_back(device_id); 205 | 206 | return result; 207 | } 208 | 209 | string 210 | read_line(const string& file) 211 | { 212 | ifstream ifs(file.c_str(), ifstream::in); 213 | 214 | string line; 215 | 216 | if(ifs) 217 | { 218 | getline(ifs, line); 219 | } 220 | 221 | return line; 222 | } 223 | 224 | string 225 | format(const char* format, ...) 226 | { 227 | va_list ap; 228 | 229 | size_t buffer_size_bytes = 256; 230 | 231 | string result; 232 | 233 | char* buffer = (char*)malloc(buffer_size_bytes); 234 | 235 | if( buffer == NULL ) 236 | return result; 237 | 238 | bool done = false; 239 | 240 | unsigned int loop_count = 0; 241 | 242 | while(!done) 243 | { 244 | va_start(ap, format); 245 | 246 | int return_value = vsnprintf(buffer, buffer_size_bytes, format, ap); 247 | 248 | if( return_value < 0 ) 249 | { 250 | done = true; 251 | } 252 | else if( return_value >= buffer_size_bytes ) 253 | { 254 | // Realloc and try again. 255 | 256 | buffer_size_bytes = return_value + 1; 257 | 258 | char* new_buffer_ptr = (char*)realloc(buffer, buffer_size_bytes); 259 | 260 | if( new_buffer_ptr == NULL ) 261 | { 262 | done = true; 263 | } 264 | else 265 | { 266 | buffer = new_buffer_ptr; 267 | } 268 | } 269 | else 270 | { 271 | result = buffer; 272 | done = true; 273 | } 274 | 275 | va_end(ap); 276 | 277 | if( ++loop_count > 5 ) 278 | done = true; 279 | } 280 | 281 | free(buffer); 282 | 283 | return result; 284 | } 285 | 286 | string 287 | usb_sysfs_hw_string(const string& sysfs_path) 288 | { 289 | string serial_number = read_line( sysfs_path + "/serial" ); 290 | 291 | if( serial_number.length() > 0 ) 292 | { 293 | serial_number = format( "SNR=%s", serial_number.c_str() ); 294 | } 295 | 296 | string vid = read_line( sysfs_path + "/idVendor" ); 297 | 298 | string pid = read_line( sysfs_path + "/idProduct" ); 299 | 300 | return format("USB VID:PID=%s:%s %s", vid.c_str(), pid.c_str(), serial_number.c_str() ); 301 | } 302 | 303 | vector 304 | serial::list_ports() 305 | { 306 | vector results; 307 | 308 | vector search_globs; 309 | search_globs.push_back("/dev/ttyACM*"); 310 | search_globs.push_back("/dev/ttyS*"); 311 | search_globs.push_back("/dev/ttyUSB*"); 312 | search_globs.push_back("/dev/tty.*"); 313 | search_globs.push_back("/dev/cu.*"); 314 | 315 | vector devices_found = glob( search_globs ); 316 | 317 | vector::iterator iter = devices_found.begin(); 318 | 319 | while( iter != devices_found.end() ) 320 | { 321 | string device = *iter++; 322 | 323 | vector sysfs_info = get_sysfs_info( device ); 324 | 325 | string friendly_name = sysfs_info[0]; 326 | 327 | string hardware_id = sysfs_info[1]; 328 | 329 | string device_id = sysfs_info[2]; 330 | 331 | std::size_t found = hardware_id.find("10c4:ea60"); 332 | 333 | if(found != std::string::npos) { 334 | PortInfo device_entry; 335 | device_entry.port = device; 336 | device_entry.description = friendly_name; 337 | device_entry.hardware_id = hardware_id; 338 | device_entry.device_id = device_id; 339 | results.push_back( device_entry ); 340 | } 341 | 342 | 343 | 344 | } 345 | 346 | return results; 347 | } 348 | 349 | #endif // defined(__linux__) 350 | -------------------------------------------------------------------------------- /Serial/impl/unix/unix.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file unix.h * 8 | * @brief unix serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | // libc dep 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | 38 | // libc++ dep 39 | #include 40 | #include 41 | 42 | // linux specific 43 | #include 44 | #include 45 | #include 46 | #include 47 | #include 48 | #include 49 | #include 50 | #include 51 | #include 52 | #include 53 | 54 | -------------------------------------------------------------------------------- /Serial/impl/unix/unix_serial.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file unix_serial.h * 8 | * @brief unix serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #if !defined(_WIN32) 28 | 29 | #ifndef SERIAL_IMPL_UNIX_H 30 | #define SERIAL_IMPL_UNIX_H 31 | 32 | #include 33 | #include 34 | #include 35 | #include 36 | 37 | namespace serial { 38 | 39 | using std::size_t; 40 | using std::string; 41 | 42 | 43 | class MillisecondTimer { 44 | public: 45 | explicit MillisecondTimer(const uint32_t millis); 46 | int64_t remaining(); 47 | 48 | private: 49 | static timespec timespec_now(); 50 | timespec expiry; 51 | }; 52 | 53 | class serial::Serial::SerialImpl { 54 | public: 55 | explicit SerialImpl (const string &port, 56 | unsigned long baudrate, 57 | bytesize_t bytesize, 58 | parity_t parity, 59 | stopbits_t stopbits, 60 | flowcontrol_t flowcontrol); 61 | 62 | virtual ~SerialImpl (); 63 | 64 | bool open (); 65 | 66 | void close (); 67 | 68 | bool isOpen () const; 69 | 70 | size_t available (); 71 | 72 | bool waitReadable (uint32_t timeout); 73 | 74 | void waitByteTimes (size_t count); 75 | 76 | int waitfordata(size_t data_count, uint32_t timeout, size_t * returned_size); 77 | 78 | size_t read (uint8_t *buf, size_t size = 1); 79 | 80 | size_t write (const uint8_t *data, size_t length); 81 | 82 | 83 | void flush (); 84 | 85 | void flushInput (); 86 | 87 | void flushOutput (); 88 | 89 | void sendBreak (int duration); 90 | 91 | bool setBreak (bool level); 92 | 93 | bool setRTS (bool level); 94 | 95 | bool setDTR (bool level); 96 | 97 | bool waitForChange (); 98 | 99 | bool getCTS (); 100 | 101 | bool getDSR (); 102 | 103 | bool getRI (); 104 | 105 | bool getCD (); 106 | 107 | uint32_t getByteTime(); 108 | 109 | void setPort (const string &port); 110 | 111 | string getPort () const; 112 | 113 | void setTimeout (Timeout &timeout); 114 | 115 | Timeout getTimeout () const; 116 | 117 | bool setBaudrate (unsigned long baudrate); 118 | 119 | bool setStandardBaudRate(speed_t baudrate); 120 | 121 | bool setCustomBaudRate(unsigned long baudrate); 122 | 123 | unsigned long getBaudrate () const; 124 | 125 | bool setBytesize (bytesize_t bytesize); 126 | 127 | bytesize_t getBytesize () const; 128 | 129 | bool setParity (parity_t parity); 130 | 131 | parity_t getParity () const; 132 | 133 | bool setStopbits (stopbits_t stopbits); 134 | 135 | stopbits_t getStopbits () const; 136 | 137 | bool setFlowcontrol (flowcontrol_t flowcontrol); 138 | 139 | flowcontrol_t getFlowcontrol () const; 140 | 141 | bool setTermios(const termios *tio); 142 | 143 | bool getTermios(termios *tio); 144 | 145 | int readLock (); 146 | 147 | int readUnlock (); 148 | 149 | int writeLock (); 150 | 151 | int writeUnlock (); 152 | 153 | 154 | private: 155 | string port_; // Path to the file descriptor 156 | int fd_; // The current file descriptor 157 | pid_t pid; 158 | 159 | bool is_open_; 160 | bool xonxoff_; 161 | bool rtscts_; 162 | 163 | Timeout timeout_; // Timeout for read operations 164 | unsigned long baudrate_; // Baudrate 165 | uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte 166 | 167 | parity_t parity_; // Parity 168 | bytesize_t bytesize_; // Size of the bytes 169 | stopbits_t stopbits_; // Stop Bits 170 | flowcontrol_t flowcontrol_; // Flow Control 171 | 172 | // Mutex used to lock the read functions 173 | pthread_mutex_t read_mutex; 174 | // Mutex used to lock the write functions 175 | pthread_mutex_t write_mutex; 176 | }; 177 | 178 | } 179 | 180 | #endif // SERIAL_IMPL_UNIX_H 181 | 182 | #endif // !defined(_WIN32) 183 | -------------------------------------------------------------------------------- /Serial/impl/windows/list_ports_win.cpp: -------------------------------------------------------------------------------- 1 | #if defined(_WIN32) 2 | 3 | /* 4 | * Copyright (c) 2014 Craig Lilley 5 | * This software is made available under the terms of the MIT licence. 6 | * A copy of the licence can be obtained from: 7 | * http://opensource.org/licenses/MIT 8 | */ 9 | 10 | #include "serial.h" 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | using serial::PortInfo; 19 | using std::vector; 20 | using std::string; 21 | 22 | static const DWORD port_name_max_length = 256; 23 | static const DWORD friendly_name_max_length = 256; 24 | static const DWORD hardware_id_max_length = 256; 25 | static const DWORD device_id_max_length = 256; 26 | 27 | 28 | // Convert a wide Unicode string to an UTF8 string 29 | std::string utf8_encode(const std::wstring &wstr) 30 | { 31 | int size_needed = WideCharToMultiByte(CP_UTF8, 0, &wstr[0], (int)wstr.size(), NULL, 0, NULL, NULL); 32 | std::string strTo( size_needed, 0 ); 33 | WideCharToMultiByte (CP_UTF8, 0, &wstr[0], (int)wstr.size(), &strTo[0], size_needed, NULL, NULL); 34 | return strTo; 35 | } 36 | 37 | vector 38 | serial::list_ports() 39 | { 40 | vector devices_found; 41 | 42 | HDEVINFO device_info_set = SetupDiGetClassDevs( 43 | (const GUID *) &GUID_DEVCLASS_PORTS, 44 | NULL, 45 | NULL, 46 | DIGCF_PRESENT); 47 | 48 | unsigned int device_info_set_index = 0; 49 | SP_DEVINFO_DATA device_info_data; 50 | 51 | device_info_data.cbSize = sizeof(SP_DEVINFO_DATA); 52 | 53 | while(SetupDiEnumDeviceInfo(device_info_set, device_info_set_index, &device_info_data)) 54 | { 55 | device_info_set_index++; 56 | 57 | // Get port name 58 | 59 | HKEY hkey = SetupDiOpenDevRegKey( 60 | device_info_set, 61 | &device_info_data, 62 | DICS_FLAG_GLOBAL, 63 | 0, 64 | DIREG_DEV, 65 | KEY_READ); 66 | 67 | TCHAR port_name[port_name_max_length]; 68 | DWORD port_name_length = port_name_max_length; 69 | 70 | LONG return_code = RegQueryValueEx( 71 | hkey, 72 | _T("PortName"), 73 | NULL, 74 | NULL, 75 | (LPBYTE)port_name, 76 | &port_name_length); 77 | 78 | RegCloseKey(hkey); 79 | 80 | if(return_code != EXIT_SUCCESS) 81 | continue; 82 | 83 | if(port_name_length > 0 && port_name_length <= port_name_max_length) 84 | port_name[port_name_length-1] = '\0'; 85 | else 86 | port_name[0] = '\0'; 87 | 88 | // Ignore parallel ports 89 | 90 | if(_tcsstr(port_name, _T("LPT")) != NULL) 91 | continue; 92 | 93 | // Get port friendly name 94 | 95 | TCHAR friendly_name[friendly_name_max_length]; 96 | DWORD friendly_name_actual_length = 0; 97 | 98 | BOOL got_friendly_name = SetupDiGetDeviceRegistryProperty( 99 | device_info_set, 100 | &device_info_data, 101 | SPDRP_FRIENDLYNAME, 102 | NULL, 103 | (PBYTE)friendly_name, 104 | friendly_name_max_length, 105 | &friendly_name_actual_length); 106 | 107 | if(got_friendly_name == TRUE && friendly_name_actual_length > 0) 108 | friendly_name[friendly_name_actual_length-1] = '\0'; 109 | else 110 | friendly_name[0] = '\0'; 111 | 112 | // Get hardware ID 113 | 114 | TCHAR hardware_id[hardware_id_max_length]; 115 | DWORD hardware_id_actual_length = 0; 116 | 117 | BOOL got_hardware_id = SetupDiGetDeviceRegistryProperty( 118 | device_info_set, 119 | &device_info_data, 120 | SPDRP_HARDWAREID, 121 | NULL, 122 | (PBYTE)hardware_id, 123 | hardware_id_max_length, 124 | &hardware_id_actual_length); 125 | 126 | if(got_hardware_id == TRUE && hardware_id_actual_length > 0) 127 | hardware_id[hardware_id_actual_length-1] = '\0'; 128 | else 129 | hardware_id[0] = '\0'; 130 | 131 | TCHAR device_id[device_id_max_length]; 132 | DWORD device_id_actual_length = 0; 133 | 134 | BOOL got_device_id = SetupDiGetDeviceRegistryProperty( 135 | device_info_set, 136 | &device_info_data, 137 | SPDRP_LOCATION_INFORMATION, 138 | NULL, 139 | (PBYTE)device_id, 140 | device_id_max_length, 141 | &device_id_actual_length); 142 | 143 | if(got_device_id == TRUE && device_id_actual_length > 0) 144 | device_id[device_id_actual_length-1] = '\0'; 145 | else 146 | device_id[0] = '\0'; 147 | 148 | 149 | 150 | #ifdef UNICODE 151 | std::string portName = utf8_encode(port_name); 152 | std::string friendlyName = utf8_encode(friendly_name); 153 | std::string hardwareId = utf8_encode(hardware_id); 154 | std::string deviceId = utf8_encode(device_id); 155 | 156 | #else 157 | std::string portName = port_name; 158 | std::string friendlyName = friendly_name; 159 | std::string hardwareId = hardware_id; 160 | std::string deviceId = device_id; 161 | #endif 162 | size_t pos = deviceId.find("#"); 163 | if( pos != std::string::npos) { 164 | deviceId = deviceId.substr(pos+1, 4); 165 | deviceId = std::to_string(atoi(deviceId.c_str())); 166 | } 167 | 168 | if( hardwareId.find("VID_10C4&PID_EA60") != std::string::npos) { 169 | PortInfo port_entry; 170 | port_entry.port = portName; 171 | port_entry.description = friendlyName; 172 | port_entry.hardware_id = hardwareId; 173 | port_entry.device_id = deviceId; 174 | devices_found.push_back(port_entry); 175 | 176 | } 177 | 178 | 179 | } 180 | 181 | SetupDiDestroyDeviceInfoList(device_info_set); 182 | 183 | return devices_found; 184 | } 185 | 186 | #endif // #if defined(_WIN32) 187 | -------------------------------------------------------------------------------- /Serial/impl/windows/win.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file win.h * 8 | * @brief windows serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | 36 | 37 | -------------------------------------------------------------------------------- /Serial/impl/windows/win_serial.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file win_serial.h * 8 | * @brief windows serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #if defined(_WIN32) 28 | 29 | #ifndef SERIAL_IMPL_WINDOWS_H 30 | #define SERIAL_IMPL_WINDOWS_H 31 | 32 | #ifndef UNICODE 33 | #define UNICODE 34 | #define UNICODE_WAS_UNDEFINED 35 | #endif 36 | #include 37 | #include 38 | #include "windows.h" 39 | 40 | #ifndef UNICODE_WAS_UNDEFINED 41 | #undef UNICODE 42 | #endif 43 | 44 | namespace serial { 45 | 46 | using std::string; 47 | using std::wstring; 48 | using std::invalid_argument; 49 | 50 | 51 | class serial::Serial::SerialImpl { 52 | public: 53 | explicit SerialImpl (const string &port, 54 | unsigned long baudrate, 55 | bytesize_t bytesize, 56 | parity_t parity, 57 | stopbits_t stopbits, 58 | flowcontrol_t flowcontrol); 59 | 60 | virtual ~SerialImpl (); 61 | 62 | bool open (); 63 | 64 | void close (); 65 | 66 | bool isOpen () const; 67 | 68 | size_t available (); 69 | 70 | bool waitReadable (uint32_t timeout); 71 | 72 | void waitByteTimes (size_t count); 73 | 74 | int waitfordata(size_t data_count, uint32_t timeout, size_t * returned_size); 75 | 76 | size_t read (uint8_t *buf, size_t size = 1); 77 | 78 | size_t write (const uint8_t *data, size_t length); 79 | 80 | void flush (); 81 | 82 | void flushInput (); 83 | 84 | void flushOutput (); 85 | 86 | void sendBreak (int duration); 87 | 88 | bool setBreak (bool level); 89 | 90 | bool setRTS (bool level); 91 | 92 | bool setDTR (bool level); 93 | 94 | bool waitForChange (); 95 | 96 | bool getCTS (); 97 | 98 | bool getDSR (); 99 | 100 | bool getRI (); 101 | 102 | bool getCD (); 103 | 104 | uint32_t getByteTime(); 105 | 106 | void setPort (const string &port); 107 | 108 | string getPort () const; 109 | 110 | void setTimeout (Timeout &timeout); 111 | 112 | Timeout getTimeout () const; 113 | 114 | bool setBaudrate (unsigned long baudrate); 115 | 116 | unsigned long getBaudrate () const; 117 | 118 | bool setBytesize (bytesize_t bytesize); 119 | 120 | bytesize_t getBytesize () const; 121 | 122 | bool setParity (parity_t parity); 123 | 124 | parity_t getParity () const; 125 | 126 | bool setStopbits (stopbits_t stopbits); 127 | 128 | stopbits_t getStopbits () const; 129 | 130 | bool setFlowcontrol (flowcontrol_t flowcontrol); 131 | 132 | flowcontrol_t getFlowcontrol () const; 133 | 134 | 135 | bool setDcb(DCB *dcb); 136 | 137 | 138 | bool getDcb(DCB *dcb); 139 | 140 | int readLock (); 141 | 142 | int readUnlock (); 143 | 144 | int writeLock (); 145 | 146 | int writeUnlock (); 147 | 148 | protected: 149 | bool reconfigurePort (); 150 | 151 | public: 152 | enum { 153 | DEFAULT_RX_BUFFER_SIZE = 2048, 154 | DEFAULT_TX_BUFFER_SIZE = 128, 155 | }; 156 | 157 | 158 | private: 159 | wstring port_; // Path to the file descriptor 160 | HANDLE fd_; 161 | OVERLAPPED _wait_o; 162 | 163 | OVERLAPPED communicationOverlapped; 164 | OVERLAPPED readCompletionOverlapped; 165 | OVERLAPPED writeCompletionOverlapped; 166 | DWORD originalEventMask; 167 | DWORD triggeredEventMask; 168 | 169 | COMMTIMEOUTS currentCommTimeouts; 170 | COMMTIMEOUTS restoredCommTimeouts; 171 | 172 | bool is_open_; 173 | 174 | Timeout timeout_; // Timeout for read operations 175 | unsigned long baudrate_; // Baudrate 176 | uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte 177 | 178 | parity_t parity_; // Parity 179 | bytesize_t bytesize_; // Size of the bytes 180 | stopbits_t stopbits_; // Stop Bits 181 | flowcontrol_t flowcontrol_; // Flow Control 182 | 183 | // Mutex used to lock the read functions 184 | HANDLE read_mutex; 185 | // Mutex used to lock the write functions 186 | HANDLE write_mutex; 187 | }; 188 | 189 | } 190 | 191 | #endif // SERIAL_IMPL_WINDOWS_H 192 | 193 | #endif // if defined(_WIN32) 194 | -------------------------------------------------------------------------------- /Serial/lock.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file lock .h * 8 | * @brief serial lock * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | 28 | #ifndef LOCK_H_ 29 | #define LOCK_H_ 30 | 31 | 32 | #ifdef HAVE_SYS_FILE_H 33 | # include 34 | #endif /* HAVE_SYS_FILE_H */ 35 | #ifdef LFS /* File Lock Server */ 36 | # include 37 | # include 38 | # include 39 | #endif /* FLS */ 40 | #if defined(__linux__) 41 | # include /* fix for linux-2.3.4? kernels */ 42 | # include 43 | # include 44 | #endif /* __linux__ */ 45 | #if defined(__sun__) 46 | # include 47 | # include 48 | #endif /* __sun__ */ 49 | #if defined(__hpux__) 50 | # include 51 | #endif /* __hpux__ */ 52 | /* FIXME -- new file */ 53 | #if defined(__APPLE__) 54 | # include 55 | # include 56 | # include 57 | # include 58 | #endif /* __APPLE__ */ 59 | #ifdef __unixware__ 60 | # include 61 | #endif /* __unixware__ */ 62 | #ifdef HAVE_PWD_H 63 | #include 64 | #endif /* HAVE_PWD_H */ 65 | #ifdef HAVE_GRP_H 66 | #include 67 | #endif /* HAVE_GRP_H */ 68 | #include 69 | #ifdef LIBLOCKDEV 70 | #include 71 | #endif /* LIBLOCKDEV */ 72 | 73 | 74 | 75 | /* Ports known on the OS */ 76 | #if defined(__linux__) 77 | # define DEVICEDIR "/dev/" 78 | # define LOCKDIR "/var/lock" 79 | # define LOCKFILEPREFIX "LCK.." 80 | # define FHS 81 | #endif /* __linux__ */ 82 | #if defined(__QNX__) 83 | # define DEVICEDIR "/dev/" 84 | # define LOCKDIR "" 85 | # define LOCKFILEPREFIX "" 86 | #endif /* qnx */ 87 | #if defined(__sgi__) || defined(sgi) 88 | # define DEVICEDIR "/dev/" 89 | # define LOCKDIR "/usr/spool/uucp" 90 | # define LOCKFILEPREFIX "LK." 91 | # define UUCP 92 | #endif /* __sgi__ || sgi */ 93 | #if defined(__FreeBSD__) 94 | # define DEVICEDIR "/dev/" 95 | # define LOCKDIR "/var/spool/lock" 96 | # define LOCKFILEPREFIX "LK.." 97 | # define UUCP 98 | #endif /* __FreeBSD__ */ 99 | #if defined(__APPLE__) 100 | # define DEVICEDIR "/dev/" 101 | /*# define LOCKDIR "/var/spool/uucp"*/ 102 | # define LOCKDIR "/var/lock" 103 | # define LOCKFILEPREFIX "LK." 104 | # define UUCP 105 | #endif /* __APPLE__ */ 106 | #if defined(__NetBSD__) 107 | # define DEVICEDIR "/dev/" 108 | # define LOCKDIR "/var/lock" 109 | /*# define LOCKDIR "/usr/spool/uucp"*/ 110 | # define LOCKFILEPREFIX "LK." 111 | # define UUCP 112 | #endif /* __NetBSD__ */ 113 | #if defined(__unixware__) 114 | # define DEVICEDIR "/dev/" 115 | /* really this only fully works for OpenServer */ 116 | # define LOCKDIR "/var/spool/uucp/" 117 | # define LOCKFILEPREFIX "LK." 118 | /* 119 | this needs work.... 120 | Jonathan Schilling writes: 121 | This is complicated because as I said in my previous mail, there are 122 | two kinds of SCO operating systems. 123 | The one that most people want gnu.io for, including the guy who 124 | asked the mailing list about SCO support a few days ago, is Open Server 125 | (a/k/a "SCO UNIX"), which is SVR3-based. This uses old-style uucp locks, 126 | of the form LCK..tty0a. That's what I implemented in the RXTX port I did, 127 | and it works correctly. 128 | The other SCO/Caldera OS, UnixWare/Open UNIX, uses the new-style 129 | SVR4 locks, of the form LK.123.123.123. These OSes are a lot like 130 | Solaris (UnixWare/Open UNIX come from AT&T SVR4 which had a joint 131 | The other SCO/Caldera OS, UnixWare/Open UNIX, uses the new-style 132 | SVR4 locks, of the form LK.123.123.123. These OSes are a lot like 133 | Solaris (UnixWare/Open UNIX come from AT&T SVR4 which had a joint 134 | heritage with Sun way back when). I saw that you added support 135 | for this form of lock by RXTX 1.4-10 ... but it gets messy because, 136 | as I said before, we use the same binary gnu.io files for both 137 | UnixWare/Open UNIX and OpenServer. Thus we can't #ifdef one or the 138 | other; it would have to be a runtime test. Your code and your macros 139 | aren't set up for doing this (understandably!). So I didn't implement 140 | these; the gnu.io locks won't fully work on UnixWare/Open UNIX 141 | as a result, which I mentioned in the Release Notes. 142 | What I would suggest is that you merge in the old-style LCK..tty0a lock 143 | code that I used, since this will satisfy 90% of the SCO users. Then 144 | I'll work on some way of getting UnixWare/Open UNIX locking to work 145 | correctly, and give you those changes at a later date. 146 | Jonathan 147 | FIXME The lock type could be passed with -DOLDUUCP or -DUUCP based on 148 | os.name in configure.in or perhaps system defines could determine the lock 149 | type. 150 | Trent 151 | */ 152 | # define OLDUUCP 153 | #endif 154 | #if defined(__hpux__) 155 | /* modif cath */ 156 | # define DEVICEDIR "/dev/" 157 | # define LOCKDIR "/var/spool/uucp" 158 | # define LOCKFILEPREFIX "LCK." 159 | # define UUCP 160 | #endif /* __hpux__ */ 161 | #if defined(__osf__) /* Digital Unix */ 162 | # define DEVICEDIR "/dev/" 163 | # define LOCKDIR "" 164 | # define LOCKFILEPREFIX "LK." 165 | # define UUCP 166 | #endif /* __osf__ */ 167 | #if defined(__sun__) /* Solaris */ 168 | # define DEVICEDIR "/dev/" 169 | # define LOCKDIR "/var/spool/locks" 170 | # define LOCKFILEPREFIX "LK." 171 | /* 172 | # define UUCP 173 | */ 174 | #endif /* __sun__ */ 175 | #if defined(__BEOS__) 176 | # define DEVICEDIR "/dev/ports/" 177 | # define LOCKDIR "" 178 | # define LOCKFILEPREFIX "" 179 | # define UUCP 180 | #endif /* __BEOS__ */ 181 | #if defined(WIN32) 182 | # define DEVICEDIR "//./" 183 | # define LOCKDIR "" 184 | # define LOCKFILEPREFIX "" 185 | #endif /* WIN32 */ 186 | 187 | /* allow people to override the directories */ 188 | /* #define USER_LOCK_DIRECTORY "/home/tjarvi/1.5/build" */ 189 | #ifdef USER_LOCK_DIRECTORY 190 | # define LOCKDIR USER_LOCK_DIRECTORY 191 | #endif /* USER_LOCK_DIRECTORY */ 192 | 193 | #ifdef DISABLE_LOCKFILES 194 | #undef UUCP 195 | #undef FHS 196 | #undef OLDUUCP 197 | #endif /* DISABLE_LOCKFILES */ 198 | 199 | /* That should be all you need to look at in this file for porting */ 200 | #ifdef LFS /* Use a Lock File Server */ 201 | # define LOCK lfs_lock 202 | # define UNLOCK lfs_unlock 203 | #elif defined(UUCP) 204 | # define LOCK uucp_lock 205 | # define UNLOCK uucp_unlock 206 | #elif defined(OLDUUCP) 207 | /* 208 | We can handle the old style if needed here see __unixware__ above. 209 | defaulting to rxtx-1.4-8 behavior for now. 210 | see also __sco__ in SerialImp.c when changing this for a possible 211 | bug 212 | FIXME 213 | */ 214 | # define LOCK fhs_lock 215 | # define UNLOCK fhs_unlock 216 | #elif defined(FHS) 217 | #ifdef LIBLOCKDEV 218 | # define LOCK lib_lock_dev_lock 219 | # define UNLOCK lib_lock_dev_unlock 220 | #else 221 | # define LOCK fhs_lock 222 | # define UNLOCK fhs_unlock 223 | #endif /* LIBLOCKDEV */ 224 | #else 225 | # define LOCK system_does_not_lock 226 | # define UNLOCK system_does_not_unlock 227 | #endif /* UUCP */ 228 | 229 | 230 | 231 | //#ifndef __WIN32__ 232 | //#define UUCP_LOCK_DIR "/var/lock" 233 | 234 | #ifdef __cplusplus 235 | extern "C" { 236 | #endif 237 | //int uucp_lock( const char *file); 238 | //int uucp_unlock(void); 239 | int check_group_uucp(); 240 | int check_lock_pid( const char *file, int openpid ); 241 | int lock_device( const char * ); 242 | void unlock_device( const char * ); 243 | int is_device_locked( const char * ); 244 | int check_lock_status( const char * ); 245 | int lfs_unlock(const char *, int ); 246 | int lfs_lock( const char *, int); 247 | int lib_lock_dev_unlock(const char *, int ); 248 | int lib_lock_dev_lock( const char *, int); 249 | void fhs_unlock(const char *, int ); 250 | int fhs_lock( const char *, int); 251 | void uucp_unlock( const char *, int ); 252 | int uucp_lock( const char *, int ); 253 | 254 | #ifdef __cplusplus 255 | } 256 | #endif 257 | 258 | //#endif 259 | 260 | #endif /* LOCK_H_ */ 261 | -------------------------------------------------------------------------------- /Serial/serial.cpp: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file serial.cpp * 8 | * @brief serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #include 28 | 29 | #if !defined(_WIN32) && !defined(__OpenBSD__) && !defined(__FreeBSD__) 30 | # include 31 | #endif 32 | 33 | #if defined (__MINGW32__) 34 | # define alloca __builtin_alloca 35 | #endif 36 | 37 | #include "serial.h" 38 | #include "common.h" 39 | 40 | namespace serial { 41 | 42 | using std::min; 43 | using std::numeric_limits; 44 | using std::vector; 45 | using std::size_t; 46 | using std::string; 47 | 48 | using serial::Serial; 49 | using serial::bytesize_t; 50 | using serial::parity_t; 51 | using serial::stopbits_t; 52 | using serial::flowcontrol_t; 53 | 54 | class Serial::ScopedReadLock { 55 | public: 56 | explicit ScopedReadLock(SerialImpl *pimpl) : pimpl_(pimpl) { 57 | this->pimpl_->readLock(); 58 | } 59 | ~ScopedReadLock() { 60 | this->pimpl_->readUnlock(); 61 | } 62 | private: 63 | // Disable copy constructors 64 | ScopedReadLock(const ScopedReadLock&); 65 | const ScopedReadLock& operator=(ScopedReadLock); 66 | 67 | SerialImpl *pimpl_; 68 | }; 69 | 70 | class Serial::ScopedWriteLock { 71 | public: 72 | explicit ScopedWriteLock(SerialImpl *pimpl) : pimpl_(pimpl) { 73 | this->pimpl_->writeLock(); 74 | } 75 | ~ScopedWriteLock() { 76 | this->pimpl_->writeUnlock(); 77 | } 78 | private: 79 | // Disable copy constructors 80 | ScopedWriteLock(const ScopedWriteLock&); 81 | const ScopedWriteLock& operator=(ScopedWriteLock); 82 | SerialImpl *pimpl_; 83 | }; 84 | 85 | Serial::Serial (const string &port, uint32_t baudrate, serial::Timeout timeout, 86 | bytesize_t bytesize, parity_t parity, stopbits_t stopbits, 87 | flowcontrol_t flowcontrol) 88 | : pimpl_(new SerialImpl (port, baudrate, bytesize, parity, 89 | stopbits, flowcontrol)) { 90 | pimpl_->setTimeout(timeout); 91 | } 92 | 93 | Serial::~Serial () { 94 | delete pimpl_; 95 | } 96 | 97 | bool Serial::open () { 98 | return pimpl_->open (); 99 | } 100 | 101 | void Serial::close () { 102 | pimpl_->close (); 103 | } 104 | 105 | bool Serial::isOpen () const { 106 | return pimpl_->isOpen (); 107 | } 108 | 109 | size_t Serial::available () { 110 | return pimpl_->available (); 111 | } 112 | 113 | bool Serial::waitReadable () { 114 | serial::Timeout timeout(pimpl_->getTimeout ()); 115 | return pimpl_->waitReadable(timeout.read_timeout_constant); 116 | } 117 | 118 | void Serial::waitByteTimes (size_t count) { 119 | pimpl_->waitByteTimes(count); 120 | } 121 | 122 | int Serial::waitfordata(size_t data_count, uint32_t timeout, size_t * returned_size) { 123 | return pimpl_->waitfordata(data_count, timeout, returned_size); 124 | } 125 | 126 | size_t Serial::read_ (uint8_t *buffer, size_t size) { 127 | return this->pimpl_->read (buffer, size); 128 | } 129 | 130 | size_t Serial::read (uint8_t *buffer, size_t size) { 131 | ScopedReadLock lock(this->pimpl_); 132 | return this->pimpl_->read (buffer, size); 133 | } 134 | 135 | size_t Serial::read (std::vector &buffer, size_t size) { 136 | ScopedReadLock lock(this->pimpl_); 137 | uint8_t *buffer_ = new uint8_t[size]; 138 | size_t bytes_read = this->pimpl_->read (buffer_, size); 139 | buffer.insert (buffer.end (), buffer_, buffer_+bytes_read); 140 | delete[] buffer_; 141 | return bytes_read; 142 | } 143 | 144 | size_t Serial::read (std::string &buffer, size_t size) { 145 | ScopedReadLock lock(this->pimpl_); 146 | uint8_t *buffer_ = new uint8_t[size]; 147 | size_t bytes_read = this->pimpl_->read (buffer_, size); 148 | buffer.append (reinterpret_cast(buffer_), bytes_read); 149 | delete[] buffer_; 150 | return bytes_read; 151 | } 152 | 153 | string Serial::read (size_t size) { 154 | std::string buffer; 155 | this->read (buffer, size); 156 | return buffer; 157 | } 158 | 159 | size_t Serial::readline (string &buffer, size_t size, string eol) { 160 | ScopedReadLock lock(this->pimpl_); 161 | size_t eol_len = eol.length (); 162 | uint8_t *buffer_ = static_cast (alloca (size * sizeof (uint8_t))); 163 | size_t read_so_far = 0; 164 | while (true) { 165 | size_t bytes_read = this->read_ (buffer_ + read_so_far, 1); 166 | read_so_far += bytes_read; 167 | if (bytes_read == 0) { 168 | break; // Timeout occured on reading 1 byte 169 | } 170 | if (string (reinterpret_cast (buffer_ + read_so_far - eol_len), eol_len) == eol) { 171 | break; // EOL found 172 | } 173 | if (read_so_far == size) { 174 | break; // Reached the maximum read length 175 | } 176 | } 177 | buffer.append(reinterpret_cast (buffer_), read_so_far); 178 | return read_so_far; 179 | } 180 | 181 | string Serial::readline (size_t size, string eol) { 182 | std::string buffer; 183 | this->readline (buffer, size, eol); 184 | return buffer; 185 | } 186 | 187 | vector Serial::readlines (size_t size, string eol) { 188 | ScopedReadLock lock(this->pimpl_); 189 | std::vector lines; 190 | size_t eol_len = eol.length (); 191 | uint8_t *buffer_ = static_cast (alloca (size * sizeof (uint8_t))); 192 | size_t read_so_far = 0; 193 | size_t start_of_line = 0; 194 | while (read_so_far < size) { 195 | size_t bytes_read = this->read_ (buffer_+read_so_far, 1); 196 | read_so_far += bytes_read; 197 | if (bytes_read == 0) { 198 | if (start_of_line != read_so_far) { 199 | lines.push_back ( string (reinterpret_cast (buffer_ + start_of_line), read_so_far - start_of_line)); 200 | } 201 | break; // Timeout occured on reading 1 byte 202 | } 203 | if (string (reinterpret_cast 204 | (buffer_ + read_so_far - eol_len), eol_len) == eol) { 205 | // EOL found 206 | lines.push_back( string(reinterpret_cast (buffer_ + start_of_line), read_so_far - start_of_line)); 207 | start_of_line = read_so_far; 208 | } 209 | if (read_so_far == size) { 210 | if (start_of_line != read_so_far) { 211 | lines.push_back( string(reinterpret_cast (buffer_ + start_of_line), read_so_far - start_of_line)); 212 | } 213 | break; // Reached the maximum read length 214 | } 215 | } 216 | return lines; 217 | } 218 | 219 | size_t Serial::write (const string &data) { 220 | ScopedWriteLock lock(this->pimpl_); 221 | return this->write_ (reinterpret_cast(data.c_str()), data.length()); 222 | } 223 | 224 | size_t Serial::write (const std::vector &data) { 225 | ScopedWriteLock lock(this->pimpl_); 226 | return this->write_ (&data[0], data.size()); 227 | } 228 | 229 | size_t Serial::write (const uint8_t *data, size_t size) { 230 | ScopedWriteLock lock(this->pimpl_); 231 | return this->write_(data, size); 232 | } 233 | 234 | size_t Serial::write_ (const uint8_t *data, size_t length) { 235 | return pimpl_->write (data, length); 236 | } 237 | 238 | void Serial::setPort (const string &port) { 239 | ScopedReadLock rlock(this->pimpl_); 240 | ScopedWriteLock wlock(this->pimpl_); 241 | bool was_open = pimpl_->isOpen (); 242 | if (was_open) close(); 243 | pimpl_->setPort (port); 244 | if (was_open) open (); 245 | } 246 | 247 | string Serial::getPort () const { 248 | return pimpl_->getPort (); 249 | } 250 | 251 | void Serial::setTimeout (serial::Timeout &timeout) { 252 | pimpl_->setTimeout (timeout); 253 | } 254 | 255 | serial::Timeout Serial::getTimeout () const { 256 | return pimpl_->getTimeout (); 257 | } 258 | 259 | bool Serial::setBaudrate (uint32_t baudrate) { 260 | return pimpl_->setBaudrate (baudrate); 261 | } 262 | 263 | uint32_t Serial::getBaudrate () const { 264 | return uint32_t(pimpl_->getBaudrate ()); 265 | } 266 | 267 | bool Serial::setBytesize (bytesize_t bytesize){ 268 | return pimpl_->setBytesize (bytesize); 269 | } 270 | 271 | bytesize_t Serial::getBytesize () const{ 272 | return pimpl_->getBytesize (); 273 | } 274 | 275 | bool Serial::setParity (parity_t parity){ 276 | return pimpl_->setParity (parity); 277 | } 278 | 279 | parity_t Serial::getParity () const{ 280 | return pimpl_->getParity (); 281 | } 282 | 283 | bool Serial::setStopbits (stopbits_t stopbits){ 284 | return pimpl_->setStopbits (stopbits); 285 | } 286 | 287 | stopbits_t Serial::getStopbits () const{ 288 | return pimpl_->getStopbits (); 289 | } 290 | 291 | bool Serial::setFlowcontrol (flowcontrol_t flowcontrol){ 292 | return pimpl_->setFlowcontrol (flowcontrol); 293 | } 294 | 295 | flowcontrol_t Serial::getFlowcontrol () const{ 296 | return pimpl_->getFlowcontrol (); 297 | } 298 | 299 | void Serial::flush (){ 300 | ScopedReadLock rlock(this->pimpl_); 301 | ScopedWriteLock wlock(this->pimpl_); 302 | pimpl_->flush (); 303 | } 304 | 305 | void Serial::flushInput (){ 306 | ScopedReadLock lock(this->pimpl_); 307 | pimpl_->flushInput (); 308 | } 309 | 310 | void Serial::flushOutput (){ 311 | ScopedWriteLock lock(this->pimpl_); 312 | pimpl_->flushOutput (); 313 | } 314 | 315 | void Serial::sendBreak (int duration){ 316 | pimpl_->sendBreak (duration); 317 | } 318 | 319 | bool Serial::setBreak (bool level){ 320 | return pimpl_->setBreak (level); 321 | } 322 | 323 | bool Serial::setRTS (bool level){ 324 | return pimpl_->setRTS (level); 325 | } 326 | 327 | bool Serial::setDTR (bool level){ 328 | return pimpl_->setDTR (level); 329 | } 330 | 331 | bool Serial::waitForChange(){ 332 | return pimpl_->waitForChange(); 333 | } 334 | 335 | bool Serial::getCTS (){ 336 | return pimpl_->getCTS (); 337 | } 338 | 339 | bool Serial::getDSR (){ 340 | return pimpl_->getDSR (); 341 | } 342 | 343 | bool Serial::getRI (){ 344 | return pimpl_->getRI (); 345 | } 346 | 347 | bool Serial::getCD (){ 348 | return pimpl_->getCD (); 349 | } 350 | 351 | uint32_t Serial::getByteTime(){ 352 | return pimpl_->getByteTime(); 353 | } 354 | } 355 | -------------------------------------------------------------------------------- /Serial/serial.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file serial.h * 8 | * @brief serial * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #ifndef SERIAL_H 28 | #define SERIAL_H 29 | 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | 37 | namespace serial { 38 | 39 | /*! 40 | * Enumeration defines the possible bytesizes for the serial port. 41 | */ 42 | typedef enum { 43 | fivebits = 5, 44 | sixbits = 6, 45 | sevenbits = 7, 46 | eightbits = 8 47 | } bytesize_t; 48 | 49 | /*! 50 | * Enumeration defines the possible parity types for the serial port. 51 | */ 52 | typedef enum { 53 | parity_none = 0, 54 | parity_odd = 1, 55 | parity_even = 2, 56 | parity_mark = 3, 57 | parity_space = 4 58 | } parity_t; 59 | 60 | /*! 61 | * Enumeration defines the possible stopbit types for the serial port. 62 | */ 63 | typedef enum { 64 | stopbits_one = 1, 65 | stopbits_two = 2, 66 | stopbits_one_point_five 67 | } stopbits_t; 68 | 69 | /*! 70 | * Enumeration defines the possible flowcontrol types for the serial port. 71 | */ 72 | typedef enum { 73 | flowcontrol_none = 0, 74 | flowcontrol_software, 75 | flowcontrol_hardware 76 | } flowcontrol_t; 77 | 78 | /*! 79 | * Structure for setting the timeout of the serial port, times are 80 | * in milliseconds. 81 | * 82 | * In order to disable the interbyte timeout, set it to Timeout::max(). 83 | */ 84 | struct Timeout { 85 | #ifdef max 86 | # undef max 87 | #endif 88 | static uint32_t max() {return std::numeric_limits::max();} 89 | /*! 90 | * Convenience function to generate Timeout structs using a 91 | * single absolute timeout. 92 | * 93 | * \param timeout A long that defines the time in milliseconds until a 94 | * timeout occurs after a call to read or write is made. 95 | * 96 | * \return Timeout struct that represents this simple timeout provided. 97 | */ 98 | static Timeout simpleTimeout(uint32_t timeout) { 99 | return Timeout(max(), timeout, 0, timeout, 0); 100 | } 101 | 102 | /*! Number of milliseconds between bytes received to timeout on. */ 103 | uint32_t inter_byte_timeout; 104 | /*! A constant number of milliseconds to wait after calling read. */ 105 | uint32_t read_timeout_constant; 106 | /*! A multiplier against the number of requested bytes to wait after 107 | * calling read. 108 | */ 109 | uint32_t read_timeout_multiplier; 110 | /*! A constant number of milliseconds to wait after calling write. */ 111 | uint32_t write_timeout_constant; 112 | /*! A multiplier against the number of requested bytes to wait after 113 | * calling write. 114 | */ 115 | uint32_t write_timeout_multiplier; 116 | 117 | explicit Timeout (uint32_t inter_byte_timeout_=0, 118 | uint32_t read_timeout_constant_=0, 119 | uint32_t read_timeout_multiplier_=0, 120 | uint32_t write_timeout_constant_=0, 121 | uint32_t write_timeout_multiplier_=0) 122 | : inter_byte_timeout(inter_byte_timeout_), 123 | read_timeout_constant(read_timeout_constant_), 124 | read_timeout_multiplier(read_timeout_multiplier_), 125 | write_timeout_constant(write_timeout_constant_), 126 | write_timeout_multiplier(write_timeout_multiplier_) 127 | {} 128 | }; 129 | 130 | /*! 131 | * Class that provides a portable serial port interface. 132 | */ 133 | class Serial { 134 | public: 135 | /*! 136 | * Creates a Serial object and opens the port if a port is specified, 137 | * otherwise it remains closed until serial::Serial::open is called. 138 | * 139 | * \param port A std::string containing the address of the serial port, 140 | * which would be something like 'COM1' on Windows and '/dev/ttyS0' 141 | * on Linux. 142 | * 143 | * \param baudrate An unsigned 32-bit integer that represents the baudrate 144 | * 145 | * \param timeout A serial::Timeout struct that defines the timeout 146 | * conditions for the serial port. \see serial::Timeout 147 | * 148 | * \param bytesize Size of each byte in the serial transmission of data, 149 | * default is eightbits, possible values are: fivebits, sixbits, sevenbits, 150 | * eightbits 151 | * 152 | * \param parity Method of parity, default is parity_none, possible values 153 | * are: parity_none, parity_odd, parity_even 154 | * 155 | * \param stopbits Number of stop bits used, default is stopbits_one, 156 | * possible values are: stopbits_one, stopbits_one_point_five, stopbits_two 157 | * 158 | * \param flowcontrol Type of flowcontrol used, default is 159 | * flowcontrol_none, possible values are: flowcontrol_none, 160 | * flowcontrol_software, flowcontrol_hardware 161 | * 162 | * \throw serial::PortNotOpenedException 163 | * \throw serial::IOException 164 | * \throw std::invalid_argument 165 | */ 166 | explicit Serial (const std::string &port = "", 167 | uint32_t baudrate = 9600, 168 | Timeout timeout = Timeout(), 169 | bytesize_t bytesize = eightbits, 170 | parity_t parity = parity_none, 171 | stopbits_t stopbits = stopbits_one, 172 | flowcontrol_t flowcontrol = flowcontrol_none); 173 | 174 | /*! Destructor */ 175 | virtual ~Serial (); 176 | 177 | /*! 178 | * Opens the serial port as long as the port is set and the port isn't 179 | * already open. 180 | * 181 | * If the port is provided to the constructor then an explicit call to open 182 | * is not needed. 183 | * 184 | * \see Serial::Serial 185 | * \return Returns true if the port is open, false otherwise. 186 | */ 187 | bool open (); 188 | 189 | /*! Gets the open status of the serial port. 190 | * 191 | * \return Returns true if the port is open, false otherwise. 192 | */ 193 | bool isOpen () const; 194 | 195 | /*! Closes the serial port. */ 196 | void close (); 197 | 198 | /*! Return the number of characters in the buffer. */ 199 | size_t available (); 200 | 201 | /*! Block until there is serial data to read or read_timeout_constant 202 | * number of milliseconds have elapsed. The return value is true when 203 | * the function exits with the port in a readable state, false otherwise 204 | * (due to timeout or select interruption). */ 205 | bool waitReadable (); 206 | 207 | /*! Block for a period of time corresponding to the transmission time of 208 | * count characters at present serial settings. This may be used in con- 209 | * junction with waitReadable to read larger blocks of data from the 210 | * port. */ 211 | void waitByteTimes (size_t count); 212 | 213 | 214 | int waitfordata(size_t data_count, uint32_t timeout, size_t * returned_size); 215 | 216 | /*! Read a given amount of bytes from the serial port into a given buffer. 217 | * 218 | * The read function will return in one of three cases: 219 | * * The number of requested bytes was read. 220 | * * In this case the number of bytes requested will match the size_t 221 | * returned by read. 222 | * * A timeout occurred, in this case the number of bytes read will not 223 | * match the amount requested, but no exception will be thrown. One of 224 | * two possible timeouts occurred: 225 | * * The inter byte timeout expired, this means that number of 226 | * milliseconds elapsed between receiving bytes from the serial port 227 | * exceeded the inter byte timeout. 228 | * * The total timeout expired, which is calculated by multiplying the 229 | * read timeout multiplier by the number of requested bytes and then 230 | * added to the read timeout constant. If that total number of 231 | * milliseconds elapses after the initial call to read a timeout will 232 | * occur. 233 | * * An exception occurred, in this case an actual exception will be thrown. 234 | * 235 | * \param buffer An uint8_t array of at least the requested size. 236 | * \param size A size_t defining how many bytes to be read. 237 | * 238 | * \return A size_t representing the number of bytes read as a result of the 239 | * call to read. 240 | * 241 | */ 242 | size_t read (uint8_t *buffer, size_t size); 243 | 244 | /*! Read a given amount of bytes from the serial port into a give buffer. 245 | * 246 | * \param buffer A reference to a std::vector of uint8_t. 247 | * \param size A size_t defining how many bytes to be read. 248 | * 249 | * \return A size_t representing the number of bytes read as a result of the 250 | * call to read. 251 | * 252 | */ 253 | size_t read (std::vector &buffer, size_t size = 1); 254 | 255 | /*! Read a given amount of bytes from the serial port into a give buffer. 256 | * 257 | * \param buffer A reference to a std::string. 258 | * \param size A size_t defining how many bytes to be read. 259 | * 260 | * \return A size_t representing the number of bytes read as a result of the 261 | * call to read. 262 | * 263 | */ 264 | size_t read (std::string &buffer, size_t size = 1); 265 | 266 | /*! Read a given amount of bytes from the serial port and return a string 267 | * containing the data. 268 | * 269 | * \param size A size_t defining how many bytes to be read. 270 | * 271 | * \return A std::string containing the data read from the port. 272 | * 273 | */ 274 | std::string read (size_t size = 1); 275 | 276 | /*! Reads in a line or until a given delimiter has been processed. 277 | * 278 | * Reads from the serial port until a single line has been read. 279 | * 280 | * \param buffer A std::string reference used to store the data. 281 | * \param size A maximum length of a line, defaults to 65536 (2^16) 282 | * \param eol A string to match against for the EOL. 283 | * 284 | * \return A size_t representing the number of bytes read. 285 | * 286 | */ 287 | size_t readline (std::string &buffer, size_t size = 65536, std::string eol = "\n"); 288 | 289 | /*! Reads in a line or until a given delimiter has been processed. 290 | * 291 | * Reads from the serial port until a single line has been read. 292 | * 293 | * \param size A maximum length of a line, defaults to 65536 (2^16) 294 | * \param eol A string to match against for the EOL. 295 | * 296 | * \return A std::string containing the line. 297 | * 298 | */ 299 | std::string readline (size_t size = 65536, std::string eol = "\n"); 300 | 301 | /*! Reads in multiple lines until the serial port times out. 302 | * 303 | * This requires a timeout > 0 before it can be run. It will read until a 304 | * timeout occurs and return a list of strings. 305 | * 306 | * \param size A maximum length of combined lines, defaults to 65536 (2^16) 307 | * 308 | * \param eol A string to match against for the EOL. 309 | * 310 | * \return A vector containing the lines. 311 | * 312 | */ 313 | std::vector readlines (size_t size = 65536, std::string eol = "\n"); 314 | 315 | /*! Write a string to the serial port. 316 | * 317 | * \param data A const reference containing the data to be written 318 | * to the serial port. 319 | * 320 | * \param size A size_t that indicates how many bytes should be written from 321 | * the given data buffer. 322 | * 323 | * \return A size_t representing the number of bytes actually written to 324 | * the serial port. 325 | * 326 | * \throw serial::PortNotOpenedException 327 | * \throw serial::SerialException 328 | * \throw serial::IOException 329 | */ 330 | size_t write (const uint8_t *data, size_t size); 331 | 332 | /*! Write a string to the serial port. 333 | * 334 | * \param data A const reference containing the data to be written 335 | * to the serial port. 336 | * 337 | * \return A size_t representing the number of bytes actually written to 338 | * the serial port. 339 | * 340 | */ 341 | size_t write (const std::vector &data); 342 | 343 | /*! Write a string to the serial port. 344 | * 345 | * \param data A const reference containing the data to be written 346 | * to the serial port. 347 | * 348 | * \return A size_t representing the number of bytes actually written to 349 | * the serial port. 350 | * 351 | */ 352 | size_t write (const std::string &data); 353 | 354 | /*! Sets the serial port identifier. 355 | * 356 | * \param port A const std::string reference containing the address of the 357 | * serial port, which would be something like 'COM1' on Windows and 358 | * '/dev/ttyS0' on Linux. 359 | * 360 | * \throw std::invalid_argument 361 | */ 362 | void setPort (const std::string &port); 363 | 364 | /*! Gets the serial port identifier. 365 | * 366 | * \see Serial::setPort 367 | * 368 | * \throw std::invalid_argument 369 | */ 370 | std::string getPort () const; 371 | 372 | /*! Sets the timeout for reads and writes using the Timeout struct. 373 | * 374 | * There are two timeout conditions described here: 375 | * * The inter byte timeout: 376 | * * The inter_byte_timeout component of serial::Timeout defines the 377 | * maximum amount of time, in milliseconds, between receiving bytes on 378 | * the serial port that can pass before a timeout occurs. Setting this 379 | * to zero will prevent inter byte timeouts from occurring. 380 | * * Total time timeout: 381 | * * The constant and multiplier component of this timeout condition, 382 | * for both read and write, are defined in serial::Timeout. This 383 | * timeout occurs if the total time since the read or write call was 384 | * made exceeds the specified time in milliseconds. 385 | * * The limit is defined by multiplying the multiplier component by the 386 | * number of requested bytes and adding that product to the constant 387 | * component. In this way if you want a read call, for example, to 388 | * timeout after exactly one second regardless of the number of bytes 389 | * you asked for then set the read_timeout_constant component of 390 | * serial::Timeout to 1000 and the read_timeout_multiplier to zero. 391 | * This timeout condition can be used in conjunction with the inter 392 | * byte timeout condition with out any problems, timeout will simply 393 | * occur when one of the two timeout conditions is met. This allows 394 | * users to have maximum control over the trade-off between 395 | * responsiveness and efficiency. 396 | * 397 | * Read and write functions will return in one of three cases. When the 398 | * reading or writing is complete, when a timeout occurs, or when an 399 | * exception occurs. 400 | * 401 | * A timeout of 0 enables non-blocking mode. 402 | * 403 | * \param timeout A serial::Timeout struct containing the inter byte 404 | * timeout, and the read and write timeout constants and multipliers. 405 | * 406 | * \see serial::Timeout 407 | */ 408 | void setTimeout (Timeout &timeout); 409 | 410 | /*! Sets the timeout for reads and writes. */ 411 | void setTimeout (uint32_t inter_byte_timeout, uint32_t read_timeout_constant, 412 | uint32_t read_timeout_multiplier, uint32_t write_timeout_constant, 413 | uint32_t write_timeout_multiplier) 414 | { 415 | Timeout timeout(inter_byte_timeout, read_timeout_constant, 416 | read_timeout_multiplier, write_timeout_constant, 417 | write_timeout_multiplier); 418 | return setTimeout(timeout); 419 | } 420 | 421 | /*! Gets the timeout for reads in seconds. 422 | * 423 | * \return A Timeout struct containing the inter_byte_timeout, and read 424 | * and write timeout constants and multipliers. 425 | * 426 | * \see Serial::setTimeout 427 | */ 428 | Timeout getTimeout () const; 429 | 430 | /*! Sets the baudrate for the serial port. 431 | * 432 | * Possible baudrates depends on the system but some safe baudrates include: 433 | * 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000, 434 | * 57600, 115200 435 | * Some other baudrates that are supported by some comports: 436 | * 128000, 153600, 230400, 256000, 460800, 921600 437 | * 438 | * \param baudrate An integer that sets the baud rate for the serial port. 439 | * 440 | */ 441 | bool setBaudrate (uint32_t baudrate); 442 | 443 | /*! Gets the baudrate for the serial port. 444 | * 445 | * \return An integer that sets the baud rate for the serial port. 446 | * 447 | * \see Serial::setBaudrate 448 | * 449 | * \ 450 | */ 451 | uint32_t getBaudrate () const; 452 | 453 | /*! Sets the bytesize for the serial port. 454 | * 455 | * \param bytesize Size of each byte in the serial transmission of data, 456 | * default is eightbits, possible values are: fivebits, sixbits, sevenbits, 457 | * eightbits 458 | * 459 | * \ 460 | */ 461 | bool setBytesize (bytesize_t bytesize); 462 | 463 | /*! Gets the bytesize for the serial port. 464 | * 465 | * \see Serial::setBytesize 466 | * 467 | * \ 468 | */ 469 | bytesize_t getBytesize () const; 470 | 471 | /*! Sets the parity for the serial port. 472 | * 473 | * \param parity Method of parity, default is parity_none, possible values 474 | * are: parity_none, parity_odd, parity_even 475 | * 476 | * \ 477 | */ 478 | bool setParity (parity_t parity); 479 | 480 | /*! Gets the parity for the serial port. 481 | * 482 | * \see Serial::setParity 483 | * 484 | * \ 485 | */ 486 | parity_t getParity () const; 487 | 488 | /*! Sets the stopbits for the serial port. 489 | * 490 | * \param stopbits Number of stop bits used, default is stopbits_one, 491 | * possible values are: stopbits_one, stopbits_one_point_five, stopbits_two 492 | * 493 | * \ 494 | */ 495 | bool setStopbits (stopbits_t stopbits); 496 | 497 | /*! Gets the stopbits for the serial port. 498 | * 499 | * \see Serial::setStopbits 500 | * 501 | * \ 502 | */ 503 | stopbits_t getStopbits () const; 504 | 505 | /*! Sets the flow control for the serial port. 506 | * 507 | * \param flowcontrol Type of flowcontrol used, default is flowcontrol_none, 508 | * possible values are: flowcontrol_none, flowcontrol_software, 509 | * flowcontrol_hardware 510 | * 511 | * \ 512 | */ 513 | bool setFlowcontrol (flowcontrol_t flowcontrol); 514 | 515 | /*! Gets the flow control for the serial port. 516 | * 517 | * \see Serial::setFlowcontrol 518 | * 519 | * \ 520 | */ 521 | flowcontrol_t getFlowcontrol () const; 522 | 523 | /*! Flush the input and output buffers */ 524 | void flush (); 525 | 526 | /*! Flush only the input buffer */ 527 | void flushInput (); 528 | 529 | /*! Flush only the output buffer */ 530 | void flushOutput (); 531 | 532 | /*! Sends the RS-232 break signal. See tcsendbreak(3). */ 533 | void sendBreak (int duration); 534 | 535 | /*! Set the break condition to a given level. Defaults to true. */ 536 | bool setBreak (bool level = true); 537 | 538 | /*! Set the RTS handshaking line to the given level. Defaults to true. */ 539 | bool setRTS (bool level = true); 540 | 541 | /*! Set the DTR handshaking line to the given level. Defaults to true. */ 542 | bool setDTR (bool level = true); 543 | 544 | /*! 545 | * Blocks until CTS, DSR, RI, CD changes or something interrupts it. 546 | * 547 | * Can throw an exception if an error occurs while waiting. 548 | * You can check the status of CTS, DSR, RI, and CD once this returns. 549 | * Uses TIOCMIWAIT via ioctl if available (mostly only on Linux) with a 550 | * resolution of less than +-1ms and as good as +-0.2ms. Otherwise a 551 | * polling method is used which can give +-2ms. 552 | * 553 | * \return Returns true if one of the lines changed, false if something else 554 | * occurred. 555 | * 556 | */ 557 | bool waitForChange (); 558 | 559 | /*! Returns the current status of the CTS line. */ 560 | bool getCTS (); 561 | 562 | /*! Returns the current status of the DSR line. */ 563 | bool getDSR (); 564 | 565 | /*! Returns the current status of the RI line. */ 566 | bool getRI (); 567 | 568 | /*! Returns the current status of the CD line. */ 569 | bool getCD (); 570 | 571 | /*! Returns the singal byte time. */ 572 | uint32_t getByteTime(); 573 | 574 | private: 575 | // Disable copy constructors 576 | Serial(const Serial&); 577 | Serial& operator=(const Serial&); 578 | 579 | // Pimpl idiom, d_pointer 580 | class SerialImpl; 581 | SerialImpl *pimpl_; 582 | 583 | // Scoped Lock Classes 584 | class ScopedReadLock; 585 | class ScopedWriteLock; 586 | 587 | // Read common function 588 | size_t read_ (uint8_t *buffer, size_t size); 589 | // Write common function 590 | size_t write_ (const uint8_t *data, size_t length); 591 | }; 592 | 593 | /*! 594 | * Structure that describes a serial device. 595 | */ 596 | struct PortInfo { 597 | 598 | /*! Address of the serial port (this can be passed to the constructor of Serial). */ 599 | std::string port; 600 | 601 | /*! Human readable description of serial device if available. */ 602 | std::string description; 603 | 604 | /*! Hardware ID (e.g. VID:PID of USB serial devices) or "n/a" if not available. */ 605 | std::string hardware_id; 606 | 607 | /*! Hardware Device ID or "" if not available. */ 608 | std::string device_id; 609 | 610 | }; 611 | 612 | /* Lists the serial ports available on the system 613 | * 614 | * Returns a vector of available serial ports, each represented 615 | * by a serial::PortInfo data structure: 616 | * 617 | * \return vector of serial::PortInfo. 618 | */ 619 | std::vector 620 | list_ports(); 621 | 622 | 623 | } // namespace serial 624 | 625 | #endif 626 | -------------------------------------------------------------------------------- /Utils.h: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file Utils.h * 8 | * @brief Driver data type * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | #if defined(_MSC_VER) 42 | #include 43 | #endif 44 | 45 | #if !defined(_MSC_VER) 46 | #include 47 | #endif 48 | 49 | #if defined(_WIN32) 50 | #if defined(YDLIDAR_API_STATIC) 51 | #define YDLIDAR_API_EXPORT 52 | #elif defined(YDLIDAR_API_EXPORTS) 53 | #define YDLIDAR_API __declspec(dllexport) 54 | #else 55 | #define YDLIDAR_API __declspec(dllimport) 56 | #endif 57 | 58 | #else 59 | #define YDLIDAR_API 60 | #endif // ifdef WIN32 61 | 62 | #define UNUSED(x) (void)x 63 | 64 | #if !defined(_MSC_VER) 65 | # define _access access 66 | #endif 67 | 68 | 69 | #if defined(_WIN32) && !defined(__MINGW32__) 70 | typedef signed char int8_t; 71 | typedef unsigned char uint8_t; 72 | typedef short int16_t; 73 | typedef unsigned short uint16_t; 74 | typedef int int32_t; 75 | typedef unsigned int uint32_t; 76 | typedef __int64 int64_t; 77 | typedef unsigned __int64 uint64_t; 78 | #else 79 | 80 | #include 81 | 82 | #endif 83 | 84 | #define __small_endian 85 | 86 | #ifndef __GNUC__ 87 | #define __attribute__(x) 88 | #endif 89 | 90 | #ifdef _AVR_ 91 | typedef uint8_t _size_t; 92 | #define THREAD_PROC 93 | #elif defined (WIN64) 94 | typedef uint64_t _size_t; 95 | #define THREAD_PROC __stdcall 96 | #elif defined (WIN32) 97 | typedef uint32_t _size_t; 98 | #define THREAD_PROC __stdcall 99 | #elif defined (_M_X64) 100 | typedef uint64_t _size_t; 101 | #define THREAD_PROC __stdcall 102 | #elif defined (__GNUC__) 103 | typedef unsigned long _size_t; 104 | #define THREAD_PROC 105 | #elif defined (__ICCARM__) 106 | typedef uint32_t _size_t; 107 | #define THREAD_PROC 108 | #endif 109 | 110 | typedef _size_t (THREAD_PROC * thread_proc_t ) ( void * ); 111 | 112 | typedef int32_t result_t; 113 | 114 | #define RESULT_OK 0 115 | #define RESULT_TIMEOUT -1 116 | #define RESULT_FAIL -2 117 | 118 | #define INVALID_TIMESTAMP (0) 119 | 120 | #if !defined(_countof) 121 | #define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0])) 122 | #endif 123 | 124 | #ifndef M_PI 125 | #define M_PI 3.1415926 126 | #endif 127 | 128 | #ifndef DEG2RAD 129 | #define DEG2RAD(x) ((x)*M_PI/180.) 130 | #endif 131 | 132 | #define LIDAR_CMD_STOP 0x65 133 | #define LIDAR_CMD_SCAN 0x60 134 | #define LIDAR_CMD_FORCE_SCAN 0x61 135 | #define LIDAR_CMD_RESET 0x80 136 | #define LIDAR_CMD_FORCE_STOP 0x00 137 | #define LIDAR_CMD_GET_EAI 0x55 138 | #define LIDAR_CMD_GET_DEVICE_INFO 0x90 139 | #define LIDAR_CMD_GET_DEVICE_HEALTH 0x92 140 | #define LIDAR_ANS_TYPE_DEVINFO 0x4 141 | #define LIDAR_ANS_TYPE_DEVHEALTH 0x6 142 | #define LIDAR_CMD_SYNC_BYTE 0xA5 143 | #define LIDAR_CMDFLAG_HAS_PAYLOAD 0x80 144 | #define LIDAR_ANS_SYNC_BYTE1 0xA5 145 | #define LIDAR_ANS_SYNC_BYTE2 0x5A 146 | #define LIDAR_ANS_TYPE_MEASUREMENT 0x81 147 | #define LIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0) 148 | #define LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2 149 | #define LIDAR_RESP_MEASUREMENT_SYNC_QUALITY_SHIFT 8 150 | #define LIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0) 151 | #define LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1 152 | #define LIDAR_RESP_MEASUREMENT_DISTANCE_SHIFT 2 153 | 154 | 155 | #define LIDAR_CMD_RUN_POSITIVE 0x06 156 | #define LIDAR_CMD_RUN_INVERSION 0x07 157 | #define LIDAR_CMD_SET_AIMSPEED_ADDMIC 0x09 158 | #define LIDAR_CMD_SET_AIMSPEED_DISMIC 0x0A 159 | #define LIDAR_CMD_SET_AIMSPEED_ADD 0x0B 160 | #define LIDAR_CMD_SET_AIMSPEED_DIS 0x0C 161 | #define LIDAR_CMD_GET_AIMSPEED 0x0D 162 | 163 | #define LIDAR_CMD_SET_SAMPLING_RATE 0xD0 164 | #define LIDAR_CMD_GET_SAMPLING_RATE 0xD1 165 | #define LIDAR_STATUS_OK 0x0 166 | #define LIDAR_STATUS_WARNING 0x1 167 | #define LIDAR_STATUS_ERROR 0x2 168 | 169 | #define LIDAR_CMD_ENABLE_LOW_POWER 0x01 170 | #define LIDAR_CMD_DISABLE_LOW_POWER 0x02 171 | #define LIDAR_CMD_STATE_MODEL_MOTOR 0x05 172 | #define LIDAR_CMD_ENABLE_CONST_FREQ 0x0E 173 | #define LIDAR_CMD_DISABLE_CONST_FREQ 0x0F 174 | 175 | #define LIDAR_CMD_SAVE_SET_EXPOSURE 0x94 176 | #define LIDAR_CMD_SET_LOW_EXPOSURE 0x95 177 | #define LIDAR_CMD_ADD_EXPOSURE 0x96 178 | #define LIDAR_CMD_DIS_EXPOSURE 0x97 179 | 180 | #define LIDAR_CMD_SET_HEART_BEAT 0xD9 181 | #define LIDAR_CMD_SET_SETPOINTSFORONERINGFLAG 0xae 182 | 183 | #define PackageSampleMaxLngth 0x100 184 | typedef enum { 185 | CT_Normal = 0, 186 | CT_RingStart = 1, 187 | CT_Tail, 188 | }CT; 189 | 190 | 191 | #define Node_Default_Quality (10) 192 | #define Node_Sync 1 193 | #define Node_NotSync 2 194 | #define PackagePaidBytes 10 195 | #define PH 0x55AA 196 | 197 | 198 | #if defined(_WIN32) 199 | #pragma pack(1) 200 | #endif 201 | 202 | 203 | namespace ydlidar { 204 | 205 | 206 | struct node_info { 207 | uint8_t sync_flag; 208 | uint16_t sync_quality;//!信号质量 209 | uint16_t angle_q6_checkbit; //!测距点角度 210 | uint16_t distance_q; //! 当前测距点距离 211 | uint64_t stamp; //! 时间戳 212 | uint8_t scan_frequence; 213 | } __attribute__((packed)) ; 214 | 215 | struct PackageNode { 216 | uint8_t PakageSampleQuality; 217 | uint16_t PakageSampleDistance; 218 | }__attribute__((packed)); 219 | 220 | struct node_package { 221 | uint16_t package_Head; 222 | uint8_t package_CT; 223 | uint8_t nowPackageNum; 224 | uint16_t packageFirstSampleAngle; 225 | uint16_t packageLastSampleAngle; 226 | uint16_t checkSum; 227 | PackageNode packageSample[PackageSampleMaxLngth]; 228 | } __attribute__((packed)) ; 229 | 230 | struct node_packages { 231 | uint16_t package_Head; 232 | uint8_t package_CT; 233 | uint8_t nowPackageNum; 234 | uint16_t packageFirstSampleAngle; 235 | uint16_t packageLastSampleAngle; 236 | uint16_t checkSum; 237 | uint16_t packageSampleDistance[PackageSampleMaxLngth]; 238 | } __attribute__((packed)) ; 239 | 240 | 241 | struct device_info{ 242 | uint8_t model; ///< 雷达型号 243 | uint16_t firmware_version; ///< 固件版本号 244 | uint8_t hardware_version; ///< 硬件版本号 245 | uint8_t serialnum[16]; ///< 系列号 246 | } __attribute__((packed)) ; 247 | 248 | struct device_health { 249 | uint8_t status; ///< 健康状体 250 | uint16_t error_code; ///< 错误代码 251 | } __attribute__((packed)) ; 252 | 253 | struct sampling_rate { 254 | uint8_t rate; ///< 采样频率 255 | } __attribute__((packed)) ; 256 | 257 | struct scan_frequency { 258 | uint32_t frequency; ///< 扫描频率 259 | } __attribute__((packed)) ; 260 | 261 | struct scan_rotation { 262 | uint8_t rotation; 263 | } __attribute__((packed)) ; 264 | 265 | struct scan_exposure { 266 | uint8_t exposure; ///< 低光功率模式 267 | } __attribute__((packed)) ; 268 | 269 | struct scan_heart_beat { 270 | uint8_t enable; ///< 掉电保护状态 271 | } __attribute__((packed)); 272 | 273 | struct scan_points { 274 | uint8_t flag; 275 | } __attribute__((packed)) ; 276 | 277 | struct function_state { 278 | uint8_t state; 279 | } __attribute__((packed)) ; 280 | 281 | struct cmd_packet { 282 | uint8_t syncByte; 283 | uint8_t cmd_flag; 284 | uint8_t size; 285 | uint8_t data; 286 | } __attribute__((packed)) ; 287 | 288 | struct lidar_ans_header { 289 | uint8_t syncByte1; 290 | uint8_t syncByte2; 291 | uint32_t size:30; 292 | uint32_t subType:2; 293 | uint8_t type; 294 | } __attribute__((packed)); 295 | 296 | 297 | //! A struct for returning configuration from the YDLIDAR 298 | struct LaserConfig { 299 | //! Start angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top. 300 | float min_angle; 301 | //! Stop angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top. 302 | float max_angle; 303 | //! Scan resolution [rad]. 304 | float ang_increment; 305 | //! Scan resoltuion [ns] 306 | float time_increment; 307 | //! Time between scans 308 | float scan_time; 309 | //! Minimum range [m] 310 | float min_range; 311 | //! Maximum range [m] 312 | float max_range; 313 | //! Range Resolution [m] 314 | float range_res; 315 | }; 316 | 317 | 318 | //! A struct for returning laser readings from the YDLIDAR 319 | //! currentAngle = min_angle + ang_increment*index 320 | //! for( int i =0; i < ranges.size(); i++) { 321 | //! double currentAngle = config.min_angle + i*config.ang_increment; 322 | //! double currentDistance = ranges[i]; 323 | //! } 324 | //! 325 | //! 326 | //! 327 | struct LaserScan { 328 | //! Array of ranges 329 | std::vector ranges; 330 | //! Array of intensities 331 | std::vector intensities; 332 | //! Self reported time stamp in nanoseconds 333 | uint64_t self_time_stamp; 334 | //! System time when first range was measured in nanoseconds 335 | uint64_t system_time_stamp; 336 | 337 | //! Configuration of scan 338 | LaserConfig config; 339 | 340 | ///lidar scan frequency 341 | float scan_frequency; 342 | }; 343 | 344 | 345 | struct LaserParamCfg 346 | { 347 | 348 | LaserParamCfg(): maxRange(16.0), minRange(0.1), maxAngle(180), 349 | minAngle(-180),scanFrequency(7), intensity(false), 350 | fixedResolution(false), exposure(false), heartBeat(false), 351 | reversion(false), autoReconnect(true), serialBaudrate(115200), 352 | sampleRate(9),serialPort("") { 353 | ignoreArray.clear(); 354 | } 355 | //! Maximum range [m] 356 | float maxRange; 357 | //! Minimum range [m] 358 | float minRange; 359 | //! Maximum angle [°] 360 | float maxAngle; 361 | //! Minimum angle [°] 362 | float minAngle; 363 | //! scan frequency [HZ] 364 | int scanFrequency; 365 | //! intensity 366 | bool intensity; 367 | //! fixed angle resolution 368 | bool fixedResolution; 369 | //! low exposure model 370 | bool exposure; 371 | //! heart beat 372 | bool heartBeat; 373 | //! reversion 374 | bool reversion; 375 | //! auto reconnect 376 | bool autoReconnect; 377 | //! baud rate 378 | int serialBaudrate; 379 | //! sample rate 380 | int sampleRate; 381 | //! serial port 382 | std::string serialPort; 383 | //! ignore angle 384 | std::vector ignoreArray; 385 | }; 386 | 387 | } 388 | 389 | // Determine if sigaction is available 390 | #if __APPLE__ || _POSIX_C_SOURCE >= 1 || _XOPEN_SOURCE || _POSIX_SOURCE 391 | #define HAS_SIGACTION 392 | #endif 393 | 394 | 395 | static volatile sig_atomic_t g_signal_status = 0; 396 | 397 | #ifdef HAS_SIGACTION 398 | static struct sigaction old_action; 399 | #else 400 | typedef void (* signal_handler_t)(int); 401 | static signal_handler_t old_signal_handler = 0; 402 | #endif 403 | 404 | #ifdef HAS_SIGACTION 405 | inline struct sigaction 406 | set_sigaction(int signal_value, const struct sigaction & action) 407 | #else 408 | inline signal_handler_t 409 | set_signal_handler(int signal_value, signal_handler_t signal_handler) 410 | #endif 411 | { 412 | #ifdef HAS_SIGACTION 413 | struct sigaction old_action; 414 | ssize_t ret = sigaction(signal_value, &action, &old_action); 415 | if (ret == -1) 416 | #else 417 | signal_handler_t old_signal_handler = std::signal(signal_value, signal_handler); 418 | // NOLINTNEXTLINE(readability/braces) 419 | if (old_signal_handler == SIG_ERR) 420 | #endif 421 | { 422 | const size_t error_length = 1024; 423 | // NOLINTNEXTLINE(runtime/arrays) 424 | char error_string[error_length]; 425 | #ifndef _WIN32 426 | #if (defined(_GNU_SOURCE) && !defined(ANDROID)) 427 | char * msg = strerror_r(errno, error_string, error_length); 428 | if (msg != error_string) { 429 | strncpy(error_string, msg, error_length); 430 | msg[error_length - 1] = '\0'; 431 | } 432 | #else 433 | int error_status = strerror_r(errno, error_string, error_length); 434 | if (error_status != 0) { 435 | throw std::runtime_error("Failed to get error string for errno: " + std::to_string(errno)); 436 | } 437 | #endif 438 | #else 439 | strerror_s(error_string, error_length, errno); 440 | #endif 441 | // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here) 442 | throw std::runtime_error( 443 | std::string("Failed to set SIGINT signal handler: (" + std::to_string(errno) + ")") + 444 | error_string); 445 | // *INDENT-ON* 446 | } 447 | 448 | #ifdef HAS_SIGACTION 449 | return old_action; 450 | #else 451 | return old_signal_handler; 452 | #endif 453 | } 454 | 455 | inline void trigger_interrupt_guard_condition(int signal_value) { 456 | g_signal_status = signal_value; 457 | signal(signal_value, SIG_DFL); 458 | } 459 | 460 | inline void 461 | #ifdef HAS_SIGACTION 462 | signal_handler(int signal_value, siginfo_t * siginfo, void * context) 463 | #else 464 | signal_handler(int signal_value) 465 | #endif 466 | { 467 | // TODO(wjwwood): remove? move to console logging at some point? 468 | printf("signal_handler(%d)\n", signal_value); 469 | 470 | #ifdef HAS_SIGACTION 471 | if (old_action.sa_flags & SA_SIGINFO) { 472 | if (old_action.sa_sigaction != NULL) { 473 | old_action.sa_sigaction(signal_value, siginfo, context); 474 | } 475 | } else { 476 | if ( 477 | old_action.sa_handler != NULL && // Is set 478 | old_action.sa_handler != SIG_DFL && // Is not default 479 | old_action.sa_handler != SIG_IGN) // Is not ignored 480 | { 481 | old_action.sa_handler(signal_value); 482 | } 483 | } 484 | #else 485 | if (old_signal_handler) { 486 | old_signal_handler(signal_value); 487 | } 488 | #endif 489 | 490 | trigger_interrupt_guard_condition(signal_value); 491 | } 492 | 493 | namespace ydlidar { 494 | 495 | inline void init(int argc, char *argv[]) { 496 | UNUSED(argc); 497 | UNUSED(argv); 498 | #ifdef HAS_SIGACTION 499 | struct sigaction action; 500 | memset(&action, 0, sizeof(action)); 501 | sigemptyset(&action.sa_mask); 502 | action.sa_sigaction = ::signal_handler; 503 | action.sa_flags = SA_SIGINFO; 504 | ::old_action = set_sigaction(SIGINT, action); 505 | set_sigaction(SIGTERM, action); 506 | 507 | #else 508 | ::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler); 509 | // Register an on_shutdown hook to restore the old signal handler. 510 | #endif 511 | } 512 | inline bool ok() { 513 | return g_signal_status == 0; 514 | } 515 | inline void shutdown() { 516 | trigger_interrupt_guard_condition(SIGINT); 517 | } 518 | 519 | inline bool fileExists(const std::string filename) { 520 | return 0 == _access(filename.c_str(), 0x00 ); // 0x00 = Check for existence only! 521 | } 522 | 523 | 524 | 525 | } 526 | 527 | -------------------------------------------------------------------------------- /config.h.in: -------------------------------------------------------------------------------- 1 | /***************************************************************************** 2 | * EAI TOF LIDAR DRIVER * 3 | * Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | * * 5 | * This file is part of EAI TOF LIDAR DRIVER. * 6 | * * 7 | * @file config.h * 8 | * @brief verison description * 9 | * Details. * 10 | * * 11 | * @author Tony.Yang * 12 | * @email chushuifurong618@eaibot.com * 13 | * @version 1.3.7(版本号) * 14 | * @date chushuifurong618@eaibot.com * 15 | * * 16 | * * 17 | *----------------------------------------------------------------------------* 18 | * Remark : Description * 19 | *----------------------------------------------------------------------------* 20 | * Change History : * 21 | * | | | * 22 | *----------------------------------------------------------------------------* 23 | * 2018/08/09 | 1.3.7 | Tony.Yang | Create file * 24 | *----------------------------------------------------------------------------* 25 | * * 26 | *****************************************************************************/ 27 | #pragma once 28 | 29 | #define YDLIDAR_VERSION "@LIDAR_VERSION@" 30 | #define SDK_VERSION "@SDK_VERSION@" 31 | -------------------------------------------------------------------------------- /image/image.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/image.png -------------------------------------------------------------------------------- /image/index-X4.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/index-X4.jpg -------------------------------------------------------------------------------- /image/step1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step1.png -------------------------------------------------------------------------------- /image/step2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step2.png -------------------------------------------------------------------------------- /image/step3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step3.png -------------------------------------------------------------------------------- /image/step4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step4.png -------------------------------------------------------------------------------- /image/step5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step5.png -------------------------------------------------------------------------------- /image/step6.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/image/step6.png -------------------------------------------------------------------------------- /simpleini/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #/***************************************************************************** 2 | #* EAI TOF LIDAR DRIVER * 3 | #* Copyright (C) 2018 EAI TEAM chushuifurong618@eaibot.com. * 4 | #* * 5 | #* This file is part of EAI TOF LIDAR DRIVER. * 6 | #* * 7 | #* @file CMakeLists.txt * 8 | #* @brief * 9 | #* Details. * 10 | #* * 11 | #* @author Tony.Yang * 12 | #* @email chushuifurong618@eaibot.com * 13 | #* @version 1.0.0(版本号) * 14 | #* @date chushuifurong618@eaibot.com * 15 | #* * 16 | #* * 17 | #*----------------------------------------------------------------------------* 18 | #* Remark : Description * 19 | #*----------------------------------------------------------------------------* 20 | #* Change History : * 21 | #* | | | * 22 | #*----------------------------------------------------------------------------* 23 | #* 2018/08/09 | 1.0.0 | Tony.Yang | Create file * 24 | #*----------------------------------------------------------------------------* 25 | #* * 26 | #*****************************************************************************/ 27 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR} ) 28 | 29 | set(HDRS 30 | LIDARDevice.h 31 | LIDARDriverInterface.h 32 | Utils.h 33 | DeviceException.h 34 | ) 35 | 36 | list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}) 37 | add_to_hal_sources(ConvertUTF.c ) 38 | add_to_hal_headers(ConvertUTF.h SimpleIni.h) 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /simpleini/ConvertUTF.c: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2001-2004 Unicode, Inc. 3 | * 4 | * Disclaimer 5 | * 6 | * This source code is provided as is by Unicode, Inc. No claims are 7 | * made as to fitness for any particular purpose. No warranties of any 8 | * kind are expressed or implied. The recipient agrees to determine 9 | * applicability of information provided. If this file has been 10 | * purchased on magnetic or optical media from Unicode, Inc., the 11 | * sole remedy for any claim will be exchange of defective media 12 | * within 90 days of receipt. 13 | * 14 | * Limitations on Rights to Redistribute This Code 15 | * 16 | * Unicode, Inc. hereby grants the right to freely use the information 17 | * supplied in this file in the creation of products supporting the 18 | * Unicode Standard, and to make copies of this file in any form 19 | * for internal or external distribution as long as this notice 20 | * remains attached. 21 | */ 22 | 23 | /* --------------------------------------------------------------------- 24 | 25 | Conversions between UTF32, UTF-16, and UTF-8. Source code file. 26 | Author: Mark E. Davis, 1994. 27 | Rev History: Rick McGowan, fixes & updates May 2001. 28 | Sept 2001: fixed const & error conditions per 29 | mods suggested by S. Parent & A. Lillich. 30 | June 2002: Tim Dodd added detection and handling of incomplete 31 | source sequences, enhanced error detection, added casts 32 | to eliminate compiler warnings. 33 | July 2003: slight mods to back out aggressive FFFE detection. 34 | Jan 2004: updated switches in from-UTF8 conversions. 35 | Oct 2004: updated to use UNI_MAX_LEGAL_UTF32 in UTF-32 conversions. 36 | 37 | See the header file "ConvertUTF.h" for complete documentation. 38 | 39 | ------------------------------------------------------------------------ */ 40 | 41 | 42 | #include "ConvertUTF.h" 43 | #ifdef CVTUTF_DEBUG 44 | #include 45 | #endif 46 | 47 | static const int halfShift = 10; /* used for shifting by 10 bits */ 48 | 49 | static const UTF32 halfBase = 0x0010000UL; 50 | static const UTF32 halfMask = 0x3FFUL; 51 | 52 | #define UNI_SUR_HIGH_START (UTF32)0xD800 53 | #define UNI_SUR_HIGH_END (UTF32)0xDBFF 54 | #define UNI_SUR_LOW_START (UTF32)0xDC00 55 | #define UNI_SUR_LOW_END (UTF32)0xDFFF 56 | #define false 0 57 | #define true 1 58 | 59 | /* --------------------------------------------------------------------- */ 60 | 61 | ConversionResult ConvertUTF32toUTF16 ( 62 | const UTF32** sourceStart, const UTF32* sourceEnd, 63 | UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) { 64 | ConversionResult result = conversionOK; 65 | const UTF32* source = *sourceStart; 66 | UTF16* target = *targetStart; 67 | while (source < sourceEnd) { 68 | UTF32 ch; 69 | if (target >= targetEnd) { 70 | result = targetExhausted; break; 71 | } 72 | ch = *source++; 73 | if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */ 74 | /* UTF-16 surrogate values are illegal in UTF-32; 0xffff or 0xfffe are both reserved values */ 75 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) { 76 | if (flags == strictConversion) { 77 | --source; /* return to the illegal value itself */ 78 | result = sourceIllegal; 79 | break; 80 | } else { 81 | *target++ = UNI_REPLACEMENT_CHAR; 82 | } 83 | } else { 84 | *target++ = (UTF16)ch; /* normal case */ 85 | } 86 | } else if (ch > UNI_MAX_LEGAL_UTF32) { 87 | if (flags == strictConversion) { 88 | result = sourceIllegal; 89 | } else { 90 | *target++ = UNI_REPLACEMENT_CHAR; 91 | } 92 | } else { 93 | /* target is a character in range 0xFFFF - 0x10FFFF. */ 94 | if (target + 1 >= targetEnd) { 95 | --source; /* Back up source pointer! */ 96 | result = targetExhausted; break; 97 | } 98 | ch -= halfBase; 99 | *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START); 100 | *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START); 101 | } 102 | } 103 | *sourceStart = source; 104 | *targetStart = target; 105 | return result; 106 | } 107 | 108 | /* --------------------------------------------------------------------- */ 109 | 110 | ConversionResult ConvertUTF16toUTF32 ( 111 | const UTF16** sourceStart, const UTF16* sourceEnd, 112 | UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags) { 113 | ConversionResult result = conversionOK; 114 | const UTF16* source = *sourceStart; 115 | UTF32* target = *targetStart; 116 | UTF32 ch, ch2; 117 | while (source < sourceEnd) { 118 | const UTF16* oldSource = source; /* In case we have to back up because of target overflow. */ 119 | ch = *source++; 120 | /* If we have a surrogate pair, convert to UTF32 first. */ 121 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) { 122 | /* If the 16 bits following the high surrogate are in the source buffer... */ 123 | if (source < sourceEnd) { 124 | ch2 = *source; 125 | /* If it's a low surrogate, convert to UTF32. */ 126 | if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) { 127 | ch = ((ch - UNI_SUR_HIGH_START) << halfShift) 128 | + (ch2 - UNI_SUR_LOW_START) + halfBase; 129 | ++source; 130 | } else if (flags == strictConversion) { /* it's an unpaired high surrogate */ 131 | --source; /* return to the illegal value itself */ 132 | result = sourceIllegal; 133 | break; 134 | } 135 | } else { /* We don't have the 16 bits following the high surrogate. */ 136 | --source; /* return to the high surrogate */ 137 | result = sourceExhausted; 138 | break; 139 | } 140 | } else if (flags == strictConversion) { 141 | /* UTF-16 surrogate values are illegal in UTF-32 */ 142 | if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) { 143 | --source; /* return to the illegal value itself */ 144 | result = sourceIllegal; 145 | break; 146 | } 147 | } 148 | if (target >= targetEnd) { 149 | source = oldSource; /* Back up source pointer! */ 150 | result = targetExhausted; break; 151 | } 152 | *target++ = ch; 153 | } 154 | *sourceStart = source; 155 | *targetStart = target; 156 | #ifdef CVTUTF_DEBUG 157 | if (result == sourceIllegal) { 158 | fprintf(stderr, "ConvertUTF16toUTF32 illegal seq 0x%04x,%04x\n", ch, ch2); 159 | fflush(stderr); 160 | } 161 | #endif 162 | return result; 163 | } 164 | 165 | /* --------------------------------------------------------------------- */ 166 | 167 | /* 168 | * Index into the table below with the first byte of a UTF-8 sequence to 169 | * get the number of trailing bytes that are supposed to follow it. 170 | * Note that *legal* UTF-8 values can't have 4 or 5-bytes. The table is 171 | * left as-is for anyone who may want to do such conversion, which was 172 | * allowed in earlier algorithms. 173 | */ 174 | static const char trailingBytesForUTF8[256] = { 175 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 176 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 177 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 178 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 179 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 180 | 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 181 | 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 182 | 2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 3,3,3,3,3,3,3,3,4,4,4,4,5,5,5,5 183 | }; 184 | 185 | /* 186 | * Magic values subtracted from a buffer value during UTF8 conversion. 187 | * This table contains as many values as there might be trailing bytes 188 | * in a UTF-8 sequence. 189 | */ 190 | static const UTF32 offsetsFromUTF8[6] = { 0x00000000UL, 0x00003080UL, 0x000E2080UL, 191 | 0x03C82080UL, 0xFA082080UL, 0x82082080UL }; 192 | 193 | /* 194 | * Once the bits are split out into bytes of UTF-8, this is a mask OR-ed 195 | * into the first byte, depending on how many bytes follow. There are 196 | * as many entries in this table as there are UTF-8 sequence types. 197 | * (I.e., one byte sequence, two byte... etc.). Remember that sequencs 198 | * for *legal* UTF-8 will be 4 or fewer bytes total. 199 | */ 200 | static const UTF8 firstByteMark[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC }; 201 | 202 | /* --------------------------------------------------------------------- */ 203 | 204 | /* The interface converts a whole buffer to avoid function-call overhead. 205 | * Constants have been gathered. Loops & conditionals have been removed as 206 | * much as possible for efficiency, in favor of drop-through switches. 207 | * (See "Note A" at the bottom of the file for equivalent code.) 208 | * If your compiler supports it, the "isLegalUTF8" call can be turned 209 | * into an inline function. 210 | */ 211 | 212 | /* --------------------------------------------------------------------- */ 213 | 214 | ConversionResult ConvertUTF16toUTF8 ( 215 | const UTF16** sourceStart, const UTF16* sourceEnd, 216 | UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) { 217 | ConversionResult result = conversionOK; 218 | const UTF16* source = *sourceStart; 219 | UTF8* target = *targetStart; 220 | while (source < sourceEnd) { 221 | UTF32 ch; 222 | unsigned short bytesToWrite = 0; 223 | const UTF32 byteMask = 0xBF; 224 | const UTF32 byteMark = 0x80; 225 | const UTF16* oldSource = source; /* In case we have to back up because of target overflow. */ 226 | ch = *source++; 227 | /* If we have a surrogate pair, convert to UTF32 first. */ 228 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) { 229 | /* If the 16 bits following the high surrogate are in the source buffer... */ 230 | if (source < sourceEnd) { 231 | UTF32 ch2 = *source; 232 | /* If it's a low surrogate, convert to UTF32. */ 233 | if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) { 234 | ch = ((ch - UNI_SUR_HIGH_START) << halfShift) 235 | + (ch2 - UNI_SUR_LOW_START) + halfBase; 236 | ++source; 237 | } else if (flags == strictConversion) { /* it's an unpaired high surrogate */ 238 | --source; /* return to the illegal value itself */ 239 | result = sourceIllegal; 240 | break; 241 | } 242 | } else { /* We don't have the 16 bits following the high surrogate. */ 243 | --source; /* return to the high surrogate */ 244 | result = sourceExhausted; 245 | break; 246 | } 247 | } else if (flags == strictConversion) { 248 | /* UTF-16 surrogate values are illegal in UTF-32 */ 249 | if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) { 250 | --source; /* return to the illegal value itself */ 251 | result = sourceIllegal; 252 | break; 253 | } 254 | } 255 | /* Figure out how many bytes the result will require */ 256 | if (ch < (UTF32)0x80) { bytesToWrite = 1; 257 | } else if (ch < (UTF32)0x800) { bytesToWrite = 2; 258 | } else if (ch < (UTF32)0x10000) { bytesToWrite = 3; 259 | } else if (ch < (UTF32)0x110000) { bytesToWrite = 4; 260 | } else { bytesToWrite = 3; 261 | ch = UNI_REPLACEMENT_CHAR; 262 | } 263 | 264 | target += bytesToWrite; 265 | if (target > targetEnd) { 266 | source = oldSource; /* Back up source pointer! */ 267 | target -= bytesToWrite; result = targetExhausted; break; 268 | } 269 | switch (bytesToWrite) { /* note: everything falls through. */ 270 | case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 271 | case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 272 | case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 273 | case 1: *--target = (UTF8)(ch | firstByteMark[bytesToWrite]); 274 | } 275 | target += bytesToWrite; 276 | } 277 | *sourceStart = source; 278 | *targetStart = target; 279 | return result; 280 | } 281 | 282 | /* --------------------------------------------------------------------- */ 283 | 284 | /* 285 | * Utility routine to tell whether a sequence of bytes is legal UTF-8. 286 | * This must be called with the length pre-determined by the first byte. 287 | * If not calling this from ConvertUTF8to*, then the length can be set by: 288 | * length = trailingBytesForUTF8[*source]+1; 289 | * and the sequence is illegal right away if there aren't that many bytes 290 | * available. 291 | * If presented with a length > 4, this returns false. The Unicode 292 | * definition of UTF-8 goes up to 4-byte sequences. 293 | */ 294 | 295 | static Boolean isLegalUTF8(const UTF8 *source, int length) { 296 | UTF8 a; 297 | const UTF8 *srcptr = source+length; 298 | switch (length) { 299 | default: return false; 300 | /* Everything else falls through when "true"... */ 301 | case 4: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false; 302 | case 3: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false; 303 | case 2: if ((a = (*--srcptr)) > 0xBF) return false; 304 | 305 | switch (*source) { 306 | /* no fall-through in this inner switch */ 307 | case 0xE0: if (a < 0xA0) return false; break; 308 | case 0xED: if (a > 0x9F) return false; break; 309 | case 0xF0: if (a < 0x90) return false; break; 310 | case 0xF4: if (a > 0x8F) return false; break; 311 | default: if (a < 0x80) return false; 312 | } 313 | 314 | case 1: if (*source >= 0x80 && *source < 0xC2) return false; 315 | } 316 | if (*source > 0xF4) return false; 317 | return true; 318 | } 319 | 320 | /* --------------------------------------------------------------------- */ 321 | 322 | /* 323 | * Exported function to return whether a UTF-8 sequence is legal or not. 324 | * This is not used here; it's just exported. 325 | */ 326 | Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd) { 327 | int length = trailingBytesForUTF8[*source]+1; 328 | if (source+length > sourceEnd) { 329 | return false; 330 | } 331 | return isLegalUTF8(source, length); 332 | } 333 | 334 | /* --------------------------------------------------------------------- */ 335 | 336 | ConversionResult ConvertUTF8toUTF16 ( 337 | const UTF8** sourceStart, const UTF8* sourceEnd, 338 | UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) { 339 | ConversionResult result = conversionOK; 340 | const UTF8* source = *sourceStart; 341 | UTF16* target = *targetStart; 342 | while (source < sourceEnd) { 343 | UTF32 ch = 0; 344 | unsigned short extraBytesToRead = trailingBytesForUTF8[*source]; 345 | if (source + extraBytesToRead >= sourceEnd) { 346 | result = sourceExhausted; break; 347 | } 348 | /* Do this check whether lenient or strict */ 349 | if (! isLegalUTF8(source, extraBytesToRead+1)) { 350 | result = sourceIllegal; 351 | break; 352 | } 353 | /* 354 | * The cases all fall through. See "Note A" below. 355 | */ 356 | switch (extraBytesToRead) { 357 | case 5: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */ 358 | case 4: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */ 359 | case 3: ch += *source++; ch <<= 6; 360 | case 2: ch += *source++; ch <<= 6; 361 | case 1: ch += *source++; ch <<= 6; 362 | case 0: ch += *source++; 363 | } 364 | ch -= offsetsFromUTF8[extraBytesToRead]; 365 | 366 | if (target >= targetEnd) { 367 | source -= (extraBytesToRead+1); /* Back up source pointer! */ 368 | result = targetExhausted; break; 369 | } 370 | if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */ 371 | /* UTF-16 surrogate values are illegal in UTF-32 */ 372 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) { 373 | if (flags == strictConversion) { 374 | source -= (extraBytesToRead+1); /* return to the illegal value itself */ 375 | result = sourceIllegal; 376 | break; 377 | } else { 378 | *target++ = UNI_REPLACEMENT_CHAR; 379 | } 380 | } else { 381 | *target++ = (UTF16)ch; /* normal case */ 382 | } 383 | } else if (ch > UNI_MAX_UTF16) { 384 | if (flags == strictConversion) { 385 | result = sourceIllegal; 386 | source -= (extraBytesToRead+1); /* return to the start */ 387 | break; /* Bail out; shouldn't continue */ 388 | } else { 389 | *target++ = UNI_REPLACEMENT_CHAR; 390 | } 391 | } else { 392 | /* target is a character in range 0xFFFF - 0x10FFFF. */ 393 | if (target + 1 >= targetEnd) { 394 | source -= (extraBytesToRead+1); /* Back up source pointer! */ 395 | result = targetExhausted; break; 396 | } 397 | ch -= halfBase; 398 | *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START); 399 | *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START); 400 | } 401 | } 402 | *sourceStart = source; 403 | *targetStart = target; 404 | return result; 405 | } 406 | 407 | /* --------------------------------------------------------------------- */ 408 | 409 | ConversionResult ConvertUTF32toUTF8 ( 410 | const UTF32** sourceStart, const UTF32* sourceEnd, 411 | UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) { 412 | ConversionResult result = conversionOK; 413 | const UTF32* source = *sourceStart; 414 | UTF8* target = *targetStart; 415 | while (source < sourceEnd) { 416 | UTF32 ch; 417 | unsigned short bytesToWrite = 0; 418 | const UTF32 byteMask = 0xBF; 419 | const UTF32 byteMark = 0x80; 420 | ch = *source++; 421 | if (flags == strictConversion ) { 422 | /* UTF-16 surrogate values are illegal in UTF-32 */ 423 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) { 424 | --source; /* return to the illegal value itself */ 425 | result = sourceIllegal; 426 | break; 427 | } 428 | } 429 | /* 430 | * Figure out how many bytes the result will require. Turn any 431 | * illegally large UTF32 things (> Plane 17) into replacement chars. 432 | */ 433 | if (ch < (UTF32)0x80) { bytesToWrite = 1; 434 | } else if (ch < (UTF32)0x800) { bytesToWrite = 2; 435 | } else if (ch < (UTF32)0x10000) { bytesToWrite = 3; 436 | } else if (ch <= UNI_MAX_LEGAL_UTF32) { bytesToWrite = 4; 437 | } else { bytesToWrite = 3; 438 | ch = UNI_REPLACEMENT_CHAR; 439 | result = sourceIllegal; 440 | } 441 | 442 | target += bytesToWrite; 443 | if (target > targetEnd) { 444 | --source; /* Back up source pointer! */ 445 | target -= bytesToWrite; result = targetExhausted; break; 446 | } 447 | switch (bytesToWrite) { /* note: everything falls through. */ 448 | case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 449 | case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 450 | case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6; 451 | case 1: *--target = (UTF8) (ch | firstByteMark[bytesToWrite]); 452 | } 453 | target += bytesToWrite; 454 | } 455 | *sourceStart = source; 456 | *targetStart = target; 457 | return result; 458 | } 459 | 460 | /* --------------------------------------------------------------------- */ 461 | 462 | ConversionResult ConvertUTF8toUTF32 ( 463 | const UTF8** sourceStart, const UTF8* sourceEnd, 464 | UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags) { 465 | ConversionResult result = conversionOK; 466 | const UTF8* source = *sourceStart; 467 | UTF32* target = *targetStart; 468 | while (source < sourceEnd) { 469 | UTF32 ch = 0; 470 | unsigned short extraBytesToRead = trailingBytesForUTF8[*source]; 471 | if (source + extraBytesToRead >= sourceEnd) { 472 | result = sourceExhausted; break; 473 | } 474 | /* Do this check whether lenient or strict */ 475 | if (! isLegalUTF8(source, extraBytesToRead+1)) { 476 | result = sourceIllegal; 477 | break; 478 | } 479 | /* 480 | * The cases all fall through. See "Note A" below. 481 | */ 482 | switch (extraBytesToRead) { 483 | case 5: ch += *source++; ch <<= 6; 484 | case 4: ch += *source++; ch <<= 6; 485 | case 3: ch += *source++; ch <<= 6; 486 | case 2: ch += *source++; ch <<= 6; 487 | case 1: ch += *source++; ch <<= 6; 488 | case 0: ch += *source++; 489 | } 490 | ch -= offsetsFromUTF8[extraBytesToRead]; 491 | 492 | if (target >= targetEnd) { 493 | source -= (extraBytesToRead+1); /* Back up the source pointer! */ 494 | result = targetExhausted; break; 495 | } 496 | if (ch <= UNI_MAX_LEGAL_UTF32) { 497 | /* 498 | * UTF-16 surrogate values are illegal in UTF-32, and anything 499 | * over Plane 17 (> 0x10FFFF) is illegal. 500 | */ 501 | if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) { 502 | if (flags == strictConversion) { 503 | source -= (extraBytesToRead+1); /* return to the illegal value itself */ 504 | result = sourceIllegal; 505 | break; 506 | } else { 507 | *target++ = UNI_REPLACEMENT_CHAR; 508 | } 509 | } else { 510 | *target++ = ch; 511 | } 512 | } else { /* i.e., ch > UNI_MAX_LEGAL_UTF32 */ 513 | result = sourceIllegal; 514 | *target++ = UNI_REPLACEMENT_CHAR; 515 | } 516 | } 517 | *sourceStart = source; 518 | *targetStart = target; 519 | return result; 520 | } 521 | 522 | /* --------------------------------------------------------------------- 523 | 524 | Note A. 525 | The fall-through switches in UTF-8 reading code save a 526 | temp variable, some decrements & conditionals. The switches 527 | are equivalent to the following loop: 528 | { 529 | int tmpBytesToRead = extraBytesToRead+1; 530 | do { 531 | ch += *source++; 532 | --tmpBytesToRead; 533 | if (tmpBytesToRead) ch <<= 6; 534 | } while (tmpBytesToRead > 0); 535 | } 536 | In UTF-8 writing code, the switches on "bytesToWrite" are 537 | similarly unrolled loops. 538 | 539 | --------------------------------------------------------------------- */ 540 | -------------------------------------------------------------------------------- /simpleini/ConvertUTF.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2001-2004 Unicode, Inc. 3 | * 4 | * Disclaimer 5 | * 6 | * This source code is provided as is by Unicode, Inc. No claims are 7 | * made as to fitness for any particular purpose. No warranties of any 8 | * kind are expressed or implied. The recipient agrees to determine 9 | * applicability of information provided. If this file has been 10 | * purchased on magnetic or optical media from Unicode, Inc., the 11 | * sole remedy for any claim will be exchange of defective media 12 | * within 90 days of receipt. 13 | * 14 | * Limitations on Rights to Redistribute This Code 15 | * 16 | * Unicode, Inc. hereby grants the right to freely use the information 17 | * supplied in this file in the creation of products supporting the 18 | * Unicode Standard, and to make copies of this file in any form 19 | * for internal or external distribution as long as this notice 20 | * remains attached. 21 | */ 22 | 23 | /* --------------------------------------------------------------------- 24 | 25 | Conversions between UTF32, UTF-16, and UTF-8. Header file. 26 | 27 | Several funtions are included here, forming a complete set of 28 | conversions between the three formats. UTF-7 is not included 29 | here, but is handled in a separate source file. 30 | 31 | Each of these routines takes pointers to input buffers and output 32 | buffers. The input buffers are const. 33 | 34 | Each routine converts the text between *sourceStart and sourceEnd, 35 | putting the result into the buffer between *targetStart and 36 | targetEnd. Note: the end pointers are *after* the last item: e.g. 37 | *(sourceEnd - 1) is the last item. 38 | 39 | The return result indicates whether the conversion was successful, 40 | and if not, whether the problem was in the source or target buffers. 41 | (Only the first encountered problem is indicated.) 42 | 43 | After the conversion, *sourceStart and *targetStart are both 44 | updated to point to the end of last text successfully converted in 45 | the respective buffers. 46 | 47 | Input parameters: 48 | sourceStart - pointer to a pointer to the source buffer. 49 | The contents of this are modified on return so that 50 | it points at the next thing to be converted. 51 | targetStart - similarly, pointer to pointer to the target buffer. 52 | sourceEnd, targetEnd - respectively pointers to the ends of the 53 | two buffers, for overflow checking only. 54 | 55 | These conversion functions take a ConversionFlags argument. When this 56 | flag is set to strict, both irregular sequences and isolated surrogates 57 | will cause an error. When the flag is set to lenient, both irregular 58 | sequences and isolated surrogates are converted. 59 | 60 | Whether the flag is strict or lenient, all illegal sequences will cause 61 | an error return. This includes sequences such as: , , 62 | or in UTF-8, and values above 0x10FFFF in UTF-32. Conformant code 63 | must check for illegal sequences. 64 | 65 | When the flag is set to lenient, characters over 0x10FFFF are converted 66 | to the replacement character; otherwise (when the flag is set to strict) 67 | they constitute an error. 68 | 69 | Output parameters: 70 | The value "sourceIllegal" is returned from some routines if the input 71 | sequence is malformed. When "sourceIllegal" is returned, the source 72 | value will point to the illegal value that caused the problem. E.g., 73 | in UTF-8 when a sequence is malformed, it points to the start of the 74 | malformed sequence. 75 | 76 | Author: Mark E. Davis, 1994. 77 | Rev History: Rick McGowan, fixes & updates May 2001. 78 | Fixes & updates, Sept 2001. 79 | 80 | ------------------------------------------------------------------------ */ 81 | 82 | /* --------------------------------------------------------------------- 83 | The following 4 definitions are compiler-specific. 84 | The C standard does not guarantee that wchar_t has at least 85 | 16 bits, so wchar_t is no less portable than unsigned short! 86 | All should be unsigned values to avoid sign extension during 87 | bit mask & shift operations. 88 | ------------------------------------------------------------------------ */ 89 | 90 | typedef unsigned int UTF32; /* at least 32 bits */ 91 | typedef unsigned short UTF16; /* at least 16 bits */ 92 | typedef unsigned char UTF8; /* typically 8 bits */ 93 | typedef unsigned char Boolean; /* 0 or 1 */ 94 | 95 | /* Some fundamental constants */ 96 | #define UNI_REPLACEMENT_CHAR (UTF32)0x0000FFFD 97 | #define UNI_MAX_BMP (UTF32)0x0000FFFF 98 | #define UNI_MAX_UTF16 (UTF32)0x0010FFFF 99 | #define UNI_MAX_UTF32 (UTF32)0x7FFFFFFF 100 | #define UNI_MAX_LEGAL_UTF32 (UTF32)0x0010FFFF 101 | 102 | typedef enum { 103 | conversionOK, /* conversion successful */ 104 | sourceExhausted, /* partial character in source, but hit end */ 105 | targetExhausted, /* insuff. room in target for conversion */ 106 | sourceIllegal /* source sequence is illegal/malformed */ 107 | } ConversionResult; 108 | 109 | typedef enum { 110 | strictConversion = 0, 111 | lenientConversion 112 | } ConversionFlags; 113 | 114 | /* This is for C++ and does no harm in C */ 115 | #ifdef __cplusplus 116 | extern "C" { 117 | #endif 118 | 119 | ConversionResult ConvertUTF8toUTF16 ( 120 | const UTF8** sourceStart, const UTF8* sourceEnd, 121 | UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags); 122 | 123 | ConversionResult ConvertUTF16toUTF8 ( 124 | const UTF16** sourceStart, const UTF16* sourceEnd, 125 | UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags); 126 | 127 | ConversionResult ConvertUTF8toUTF32 ( 128 | const UTF8** sourceStart, const UTF8* sourceEnd, 129 | UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags); 130 | 131 | ConversionResult ConvertUTF32toUTF8 ( 132 | const UTF32** sourceStart, const UTF32* sourceEnd, 133 | UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags); 134 | 135 | ConversionResult ConvertUTF16toUTF32 ( 136 | const UTF16** sourceStart, const UTF16* sourceEnd, 137 | UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags); 138 | 139 | ConversionResult ConvertUTF32toUTF16 ( 140 | const UTF32** sourceStart, const UTF32* sourceEnd, 141 | UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags); 142 | 143 | Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd); 144 | 145 | #ifdef __cplusplus 146 | } 147 | #endif 148 | 149 | /* --------------------------------------------------------------------- */ 150 | -------------------------------------------------------------------------------- /simpleini/LICENCE.txt: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2006-2013 Brodie Thiesfield 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | this software and associated documentation files (the "Software"), to deal in 7 | the Software without restriction, including without limitation the rights to 8 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | the Software, and to permit persons to whom the Software is furnished to do so, 10 | subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 17 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | -------------------------------------------------------------------------------- /simpleini/README.md: -------------------------------------------------------------------------------- 1 | simpleini 2 | ========= 3 | 4 | [![TravisCI Status](https://travis-ci.org/brofield/simpleini.svg?branch=master)](https://travis-ci.org/brofield/simpleini) 5 | 6 | A cross-platform library that provides a simple API to read and write INI-style configuration files. It supports data files in ASCII, MBCS and Unicode. It is designed explicitly to be portable to any platform and has been tested on Windows, WinCE and Linux. Released as open-source and free using the MIT licence. 7 | 8 | # Feature Summary 9 | 10 | - MIT Licence allows free use in all software (including GPL and commercial) 11 | - multi-platform (Windows 95/98/ME/NT/2K/XP/2003, Windows CE, Linux, Unix) 12 | - loading and saving of INI-style configuration files 13 | - configuration files can have any newline format on all platforms 14 | - liberal acceptance of file format 15 | * key/values with no section 16 | * removal of whitespace around sections, keys and values 17 | - support for multi-line values (values with embedded newline characters) 18 | - optional support for multiple keys with the same name 19 | - optional case-insensitive sections and keys (for ASCII characters only) 20 | - saves files with sections and keys in the same order as they were loaded 21 | - preserves comments on the file, section and keys where possible. 22 | - supports both char or wchar_t programming interfaces 23 | - supports both MBCS (system locale) and UTF-8 file encodings 24 | - system locale does not need to be UTF-8 on Linux/Unix to load UTF-8 file 25 | - support for non-ASCII characters in section, keys, values and comments 26 | - support for non-standard character types or file encodings via user-written converter classes 27 | - support for adding/modifying values programmatically 28 | - compiles cleanly in the following compilers: 29 | * Windows/VC6 (warning level 3) 30 | * Windows/VC.NET 2003 (warning level 4) 31 | * Windows/VC 2005 (warning level 4) 32 | * Linux/gcc (-Wall) 33 | * Windows/MinGW GCC 34 | 35 | # Documentation 36 | 37 | Full documentation of the interface is available in doxygen format. 38 | 39 | # Examples 40 | 41 | These snippets are included with the distribution in the file snippets.cpp. 42 | 43 | ### SIMPLE USAGE 44 | 45 | ```c++ 46 | CSimpleIniA ini; 47 | ini.SetUnicode(); 48 | ini.LoadFile("myfile.ini"); 49 | const char * pVal = ini.GetValue("section", "key", "default"); 50 | ini.SetValue("section", "key", "newvalue"); 51 | ``` 52 | 53 | ### LOADING DATA 54 | 55 | ```c++ 56 | // load from a data file 57 | CSimpleIniA ini(a_bIsUtf8, a_bUseMultiKey, a_bUseMultiLine); 58 | SI_Error rc = ini.LoadFile(a_pszFile); 59 | if (rc < 0) return false; 60 | 61 | // load from a string 62 | std::string strData; 63 | rc = ini.LoadData(strData.c_str(), strData.size()); 64 | if (rc < 0) return false; 65 | ``` 66 | 67 | ### GETTING SECTIONS AND KEYS 68 | 69 | ```c++ 70 | // get all sections 71 | CSimpleIniA::TNamesDepend sections; 72 | ini.GetAllSections(sections); 73 | 74 | // get all keys in a section 75 | CSimpleIniA::TNamesDepend keys; 76 | ini.GetAllKeys("section-name", keys); 77 | ``` 78 | 79 | ### GETTING VALUES 80 | 81 | ```c++ 82 | // get the value of a key 83 | const char * pszValue = ini.GetValue("section-name", 84 | "key-name", NULL /*default*/); 85 | 86 | // get the value of a key which may have multiple 87 | // values. If bHasMultipleValues is true, then just 88 | // one value has been returned 89 | bool bHasMultipleValues; 90 | pszValue = ini.GetValue("section-name", "key-name", 91 | NULL /*default*/, &bHasMultipleValues); 92 | 93 | // get all values of a key with multiple values 94 | CSimpleIniA::TNamesDepend values; 95 | ini.GetAllValues("section-name", "key-name", values); 96 | 97 | // sort the values into the original load order 98 | values.sort(CSimpleIniA::Entry::LoadOrder()); 99 | 100 | // output all of the items 101 | CSimpleIniA::TNamesDepend::const_iterator i; 102 | for (i = values.begin(); i != values.end(); ++i) { 103 | printf("key-name = '%s'\n", i->pItem); 104 | } 105 | ``` 106 | 107 | ### MODIFYING DATA 108 | 109 | ```c++ 110 | // adding a new section 111 | rc = ini.SetValue("new-section", NULL, NULL); 112 | if (rc < 0) return false; 113 | printf("section: %s\n", rc == SI_INSERTED ? 114 | "inserted" : "updated"); 115 | 116 | // adding a new key ("new-section" will be added 117 | // automatically if it doesn't already exist) 118 | rc = ini.SetValue("new-section", "new-key", "value"); 119 | if (rc < 0) return false; 120 | printf("key: %s\n", rc == SI_INSERTED ? 121 | "inserted" : "updated"); 122 | 123 | // changing the value of a key 124 | rc = ini.SetValue("section", "key", "updated-value"); 125 | if (rc < 0) return false; 126 | printf("key: %s\n", rc == SI_INSERTED ? 127 | "inserted" : "updated"); 128 | ``` 129 | 130 | ### DELETING DATA 131 | 132 | ```c++ 133 | // deleting a key from a section. Optionally the entire 134 | // section may be deleted if it is now empty. 135 | ini.Delete("section-name", "key-name", 136 | true /*delete the section if empty*/); 137 | 138 | // deleting an entire section and all keys in it 139 | ini.Delete("section-name", NULL); 140 | ``` 141 | 142 | ### SAVING DATA 143 | 144 | ```c++ 145 | // save the data to a string 146 | rc = ini.Save(strData); 147 | if (rc < 0) return false; 148 | 149 | // save the data back to the file 150 | rc = ini.SaveFile(a_pszFile); 151 | if (rc < 0) return false; 152 | ``` 153 | -------------------------------------------------------------------------------- /startup/initenv.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | echo 'KERNEL=="ttyUSB[1-9]*", MODE:="0666", GROUP:="dialout"' >/etc/udev/rules.d/50-usb-serial.rules.rules 3 | echo 'KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", MODE:="0666", GROUP:="dialout", SYMLINK+="ydlidar"' >/etc/udev/rules.d/ydlidar.rules 4 | echo 'KERNEL=="ttyACM*", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", MODE:="0666", GROUP:="dialout", SYMLINK+="ydlidar"' >/etc/udev/rules.d/ydlidar-V2.rules 5 | echo 'KERNEL=="ttyUSB*", ATTRS{idVendor}=="067b", ATTRS{idProduct}=="2303", MODE:="0666", GROUP:="dialout", SYMLINK+="ydlidar"' >/etc/udev/rules.d/ydlidar-2303.rules 6 | 7 | service udev reload 8 | sleep 2 9 | service udev restart 10 | -------------------------------------------------------------------------------- /ydlidar_sdk.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/yangfuyuan/ydlidar_sdk/7cdf1e190fe0b893e87c1065464b07cfb4b26d2b/ydlidar_sdk.pdf --------------------------------------------------------------------------------