diff --git a/.gitignore b/.gitignore index 4fb3412..71660fc 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,3 @@ *.json build/** -src/test_sys/build/** \ No newline at end of file +sample/windows/build/** \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 88bb56d..2e7efd0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,15 +12,6 @@ else() message(STATUS "other platform: ${CMAKE_SYSTEM_NAME}") endif (CMAKE_SYSTEM_NAME MATCHES "Linux") -if(WIN32) - message(STATUS "Now is windows") -elseif(APPLE) - message(STATUS "Now is Apple systens.") -elseif(UNIX) - message(STATUS "Now is UNIX-like OS's.") -endif() -message(STATUS "###################################") - if(${CMAKE_BUILD_TYPE} MATCHES "Release") set(CMAKE_CXX_FLAGS_RELEASE "$ENV{CXXFLAGS} -std=c++11 -Wall") diff --git a/include/ldlidar_driver/ldlidar_datatype.h b/include/ldlidar_driver/ldlidar_datatype.h index 0bf66dc..9de366b 100644 --- a/include/ldlidar_driver/ldlidar_datatype.h +++ b/include/ldlidar_driver/ldlidar_datatype.h @@ -26,6 +26,8 @@ #include #include +#define LDLiDAR_SDK_VERSION_NUMBER "3.1.0" + #define ANGLE_TO_RADIAN(angle) ((angle)*3141.59 / 180000) // lidar error code definition diff --git a/include/ldlidar_driver/lipkg.h b/include/ldlidar_driver/lipkg.h index f0a055d..fc18889 100644 --- a/include/ldlidar_driver/lipkg.h +++ b/include/ldlidar_driver/lipkg.h @@ -39,6 +39,7 @@ enum { POINT_PER_PACK = 12, }; +#ifdef __linux__ typedef struct __attribute__((packed)) { uint16_t distance; uint8_t intensity; @@ -54,6 +55,27 @@ typedef struct __attribute__((packed)) { uint16_t timestamp; uint8_t crc8; } LiDARFrameType; +#else + +#pragma pack(1) +typedef struct { + uint16_t distance; + uint8_t intensity; +} LidarPointStructType; + +typedef struct { + uint8_t header; + uint8_t ver_len; + uint16_t speed; + uint16_t start_angle; + LidarPointStructType point[POINT_PER_PACK]; + uint16_t end_angle; + uint16_t timestamp; + uint8_t crc8; +} LiDARFrameType; +#pragma pack() + +#endif class LiPkg { public: diff --git a/include/ldlidar_driver/log_module.h b/include/ldlidar_driver/log_module.h index 92f2579..0ac7fcf 100644 --- a/include/ldlidar_driver/log_module.h +++ b/include/ldlidar_driver/log_module.h @@ -15,12 +15,11 @@ * See the License for the specific language governing permissions and * limitations under the License. **/ + #ifndef __LOGMODULE_H_ #define __LOGMODULE_H_ -#define LINUX - #define ENABLE_LOG_DIS_OUTPUT #define ENABLE_CONSOLE_LOG_DISPALY @@ -32,7 +31,7 @@ #include #include -#ifndef LINUX +#ifndef __linux__ #include #else //#include @@ -108,7 +107,7 @@ class LogPrint :public ILogRealization { } }; -#ifndef LINUX +#ifndef __linux__ class LogOutputString :public ILogRealization { public: virtual void Initializion(const char* path = NULL) { @@ -116,8 +115,17 @@ class LogOutputString :public ILogRealization { } virtual void LogPrintInf(const char* str) { - OutputDebugString((LPCTSTR)str); - OutputDebugString("\r\n"); + //OutputDebugString((LPCTSTR)str); // 将字符串发送到调试器进行显示。 + //OutputDebugString("\r\n"); + + printf("%s\r\n", str); // 将字符串发送到控制台显示 + } + + virtual void LogPrintData(const char* str) { + //OutputDebugString((LPCTSTR)str); // 将字符串发送到调试器进行显示。 + //OutputDebugString("\r\n"); + + printf("%s\r\n", str); // 将字符串发送到控制台显示 } ILOGFREE(LogOutputString) @@ -186,7 +194,7 @@ class LogModule { static LogModule* s_plog_module_; -#ifndef LINUX +#ifndef __linux__ CRITICAL_SECTION mutex_lock_; #else pthread_mutex_t mutex_lock_; diff --git a/sample/windows/CMakeLists.txt b/sample/windows/CMakeLists.txt new file mode 100644 index 0000000..7c4b38d --- /dev/null +++ b/sample/windows/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.5) + +project (ldlidar_driver_win LANGUAGES CXX) + +include_directories( + ${PROJECT_SOURCE_DIR}/ + ${PROJECT_SOURCE_DIR}/../../include +) + +add_executable(demo + ${PROJECT_SOURCE_DIR}/windemo.cpp + ${PROJECT_SOURCE_DIR}/ldlidar_driver_win.cpp + ${PROJECT_SOURCE_DIR}/commport.cpp + ${PROJECT_SOURCE_DIR}/../../src/ldlidar_driver/lipkg.cpp + ${PROJECT_SOURCE_DIR}/../../src/ldlidar_driver/log_module.cpp + ${PROJECT_SOURCE_DIR}/../../src/ldlidar_driver/sl_transform.cpp + ${PROJECT_SOURCE_DIR}/../../src/ldlidar_driver/slbf.cpp + ${PROJECT_SOURCE_DIR}/../../src/ldlidar_driver/tofbf.cpp +) +target_compile_features(demo PUBLIC cxx_std_11) \ No newline at end of file diff --git a/sample/windows/README_CN.md b/sample/windows/README_CN.md new file mode 100644 index 0000000..3ef08fa --- /dev/null +++ b/sample/windows/README_CN.md @@ -0,0 +1,12 @@ +# 使用CMake生成visual studio C++ 工程 +> 前提条件,PC上需要提前安装有visual studio IDE 和 CMake Tool。 + +## 方法一:命令行方式 +- 在`sample/windows`目录下打开powershell终端,以创建`Visual Studio 15 2017 Win64`环境下的C++工程为例,运行如下命令。 +```ps1 +mkdir build + +cd build + +cmake -G "Visual Studio 15 2017 Win64" ../ +``` \ No newline at end of file diff --git a/sample/windows/commport.cpp b/sample/windows/commport.cpp new file mode 100644 index 0000000..ca04293 --- /dev/null +++ b/sample/windows/commport.cpp @@ -0,0 +1,330 @@ +/** + * @file serial_interface_windows.cpp + * @author LDRobot (support@ldrobot.com) + * @brief Win32 serial port App + * @version 0.1 + * @date 2021-10-28 + * + * @copyright Copyright (c) 2021 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "commport.h" +#include "ldlidar_driver/log_module.h" + +#include +#include +#include + +#include +#include +#include +#include + +#pragma comment(lib, "SetupAPI.lib") +#pragma comment(lib, "Cfgmgr32.lib") + +using namespace std; + +CommPort::CommPort() + : mIsOpened(false), + mByteToRead(4096), + mRxCounter(0), + mTxCounter(0), + commErrorHandle(nullptr), + readCallback(nullptr), + mRxThread(nullptr), + mMaxBuffSize(4096) { + mComHandle = INVALID_HANDLE_VALUE; + memset(&mOverlappedSend, 0, sizeof(OVERLAPPED)); + memset(&mOverlappedRecv, 0, sizeof(OVERLAPPED)); + mOverlappedSend.hEvent = CreateEvent(NULL, FALSE, FALSE, NULL); + mOverlappedRecv.hEvent = CreateEvent(NULL, FALSE, FALSE, NULL); +} + +CommPort::~CommPort() { + if (mOverlappedRecv.hEvent != INVALID_HANDLE_VALUE) { + CloseHandle(mOverlappedRecv.hEvent); + mOverlappedRecv.hEvent = INVALID_HANDLE_VALUE; + } + if (mOverlappedSend.hEvent != INVALID_HANDLE_VALUE) { + CloseHandle(mOverlappedSend.hEvent); + mOverlappedSend.hEvent = INVALID_HANDLE_VALUE; + } +} + +std::string wcharToChar(const wchar_t *wp, UINT encode = CP_ACP) { + std::string str; + int len = + WideCharToMultiByte(encode, 0, wp, (int)wcslen(wp), NULL, 0, NULL, NULL); + char *m_char = new char[len + 1]; + WideCharToMultiByte(encode, 0, wp, (int)wcslen(wp), m_char, len, NULL, NULL); + m_char[len] = '\0'; + str = m_char; + delete m_char; + return str; +} + +bool CommPort::availablePorts(vector &availabelPortInfo) { + DWORD dwGuids = 0; + TCHAR propBuf[1024]; + PortInfo portInfo; + + availabelPortInfo.clear(); + + SetupDiClassGuidsFromName(_T("Ports"), NULL, 0, &dwGuids); + if (dwGuids == 0) return false; + + GUID *pGuids = new GUID[dwGuids]; + SetupDiClassGuidsFromName(_T("Ports"), pGuids, dwGuids, &dwGuids); + + for (DWORD i = 0; i < dwGuids; i++) { + HDEVINFO hDevInfo = + SetupDiGetClassDevs(&pGuids[i], NULL, NULL, DIGCF_PRESENT); + if (hDevInfo == INVALID_HANDLE_VALUE) break; + + for (int index = 0;; index++) { + SP_DEVINFO_DATA devInfoData; + + devInfoData.cbSize = sizeof(SP_DEVINFO_DATA); + + if (!SetupDiEnumDeviceInfo(hDevInfo, index, &devInfoData)) { + break; + } + propBuf[0] = 0; + + CM_Get_Device_ID(devInfoData.DevInst, propBuf, 1024, 0); + + string s(propBuf); + + string wusb = s.substr(0, 3); + + if (wusb == "USB") { + portInfo.vid = s.substr(8, 4); + portInfo.pid = s.substr(17, 4); + } else { + portInfo.pid = "None"; + portInfo.vid = "None"; + } + + if (!SetupDiGetDeviceRegistryProperty(hDevInfo, &devInfoData, + SPDRP_DEVICEDESC, NULL, + (PBYTE)propBuf, MAX_PATH - 1, NULL)) + continue; + + portInfo.description = propBuf; + + HKEY hDeviceKey = + SetupDiOpenDevRegKey(hDevInfo, &devInfoData, DICS_FLAG_GLOBAL, 0, + DIREG_DEV, KEY_QUERY_VALUE); + if (hDeviceKey) { + propBuf[0] = 0; + DWORD dw_size = sizeof(propBuf); + DWORD dw_type = 0; + + if ((RegQueryValueEx(hDeviceKey, _T("PortName"), NULL, &dw_type, + (LPBYTE)propBuf, &dw_size) == ERROR_SUCCESS) && + (dw_type == REG_SZ)) { + portInfo.name = propBuf; + availabelPortInfo.push_back(portInfo); + } + } + } + SetupDiDestroyDeviceInfoList(hDevInfo); + } + delete[] pGuids; + + return true; +} + +bool CommPort::open(string portName) { + if (mIsOpened) close(); + + portParams.portName = portName; + + std::string name = "\\\\.\\" + portName; + + mComHandle = ::CreateFile(name.c_str(), GENERIC_READ | GENERIC_WRITE, 0, NULL, + OPEN_EXISTING, + FILE_ATTRIBUTE_NORMAL | FILE_FLAG_OVERLAPPED, NULL); + + if (mComHandle == INVALID_HANDLE_VALUE) { + CloseHandle(mComHandle); + return false; + } + + PurgeComm(mComHandle, + PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR); + if (SetupComm(mComHandle, (DWORD)mMaxBuffSize, (DWORD)mMaxBuffSize) == 0) { + CloseHandle(mComHandle); + return false; + } + + DCB dcb; + dcb.DCBlength = sizeof(DCB); + if (GetCommState(mComHandle, &dcb) == 0) { + CloseHandle(mComHandle); + return false; + } else { + dcb.BaudRate = (DWORD)portParams.baudrate; + dcb.ByteSize = (BYTE)portParams.dataBits; + dcb.Parity = (BYTE)portParams.parity; + dcb.StopBits = (BYTE)portParams.stopBits; + if (portParams.flowControl == FlowControl::SoftwareControl) { + dcb.fOutX = 1; + dcb.fInX = 1; + } else if (portParams.flowControl == FlowControl::HardwareControl) { + dcb.fRtsControl = 0; + dcb.fDtrControl = 1; + } else { + dcb.fOutX = 0; + dcb.fInX = 0; + dcb.fRtsControl = 0; + dcb.fDtrControl = 0; + } + + if (SetCommState(mComHandle, &dcb) == 0) { + CloseHandle(mComHandle); + return false; + } + } + + COMMTIMEOUTS timeouts; + timeouts.ReadIntervalTimeout = 2; + timeouts.ReadTotalTimeoutMultiplier = 0; + timeouts.ReadTotalTimeoutConstant = 5; + timeouts.WriteTotalTimeoutConstant = 50000; + timeouts.WriteTotalTimeoutMultiplier = 1000; + SetCommTimeouts(mComHandle, &timeouts); + + mIsOpened = true; + + mRxThreadRunFlag = true; + mRxThread = new std::thread(rxThreadProc, this); + + return true; +} + +bool CommPort::close() { + if (!mIsOpened) return true; + + mIsOpened = false; + mRxThreadRunFlag = false; + + if (mComHandle != INVALID_HANDLE_VALUE) { + CloseHandle(mComHandle); + mComHandle = INVALID_HANDLE_VALUE; + } + + try { + if (mRxThread->joinable()) mRxThread->join(); + } catch (const std::system_error &e) { + // std::cout << "Caught system_error with code " << e.code() << " meaning " + // << e.what() << '\n'; + LOG_INFO("Caught system_error with code:%d, meaning:%s", e.code(), e.what()); + } + delete mRxThread; + mRxThread = nullptr; + + return true; +} + +int CommPort::readAll() { return 0; } + +bool CommPort::write(const char *txBuf, uint32_t txBufLen) { + DWORD txLen = 0; + if (mIsOpened) { + ResetEvent(mOverlappedSend.hEvent); + uint32_t res = WriteFile(mComHandle, txBuf, txBufLen, (LPDWORD)&txLen, + &mOverlappedSend); + if (!res) { + if (GetLastError() == ERROR_IO_PENDING) { + WaitForSingleObject(mOverlappedSend.hEvent, INFINITE); + GetOverlappedResult(mComHandle, &mOverlappedSend, (LPDWORD)&txLen, + FALSE); + mTxCounter += txLen; + return true; + } + } + } + + return false; +} + +void CommPort::setPortParams(PortParams params) { + memcpy(&portParams, ¶ms, sizeof(params)); +} + +PortParams CommPort::currPortParams(void) { return portParams; } + +void CommPort::rxThreadProc(CommPort *pClass) { + char *rxBuf = new char[pClass->mMaxBuffSize + 1]; + ResetEvent(pClass->mOverlappedRecv.hEvent); + LOG_INFO("rx thread start...",""); + + map error_code{ + {ERROR_INVALID_PARAMETER, "Invalid parameter"}, + {ERROR_ACCESS_DENIED, "Access denied"}, + {ERROR_INVALID_HANDLE, "Open failed"}, + {ERROR_BAD_COMMAND, "Illegal disconnection"}, + }; + + while (pClass->mRxThreadRunFlag) { + uint32_t readed = 0; + bool res = ReadFile(pClass->mComHandle, rxBuf, (DWORD)pClass->mByteToRead, + (LPDWORD)&readed, &pClass->mOverlappedRecv); + if (res == FALSE) { + long last_error = GetLastError(); + switch (last_error) { + case ERROR_IO_PENDING: { + if (WaitForSingleObject(pClass->mOverlappedRecv.hEvent, INFINITE) == + WAIT_OBJECT_0) { + GetOverlappedResult(pClass->mComHandle, &pClass->mOverlappedRecv, + (LPDWORD)&readed, FALSE); + if (readed) { + pClass->mRxCounter += readed; + // callback + if (pClass->readCallback != nullptr) { + pClass->readCallback(rxBuf, readed); + } + } + } + break; + } + case ERROR_INVALID_PARAMETER: /// 系统错误 erroe code:87 + case ERROR_ACCESS_DENIED: /// 拒绝访问 erroe code:5 + case ERROR_INVALID_HANDLE: /// 打开串口失败 erroe code:6 + case ERROR_BAD_COMMAND: /// 连接过程中非法断开 erroe code:22 + { + /// 不能再这里及回调函数中调用close,因为close中有join。在当前线程中join自己,会造成死锁 + if (pClass->commErrorHandle != nullptr) + pClass->commErrorHandle(error_code[last_error]); + pClass->mRxThreadRunFlag = false; + + break; + } + + default: /// 发生其他错误,其中有串口读写中断开串口连接的错误(错误22) + { + if (pClass->commErrorHandle != nullptr) + pClass->commErrorHandle("Unknow error"); + break; + } + } + + ResetEvent(pClass->mOverlappedRecv.hEvent); + } + } + + delete[] rxBuf; +} + +/********************* (C) COPYRIGHT LD Robot *******END OF FILE ********/ \ No newline at end of file diff --git a/sample/windows/commport.h b/sample/windows/commport.h new file mode 100644 index 0000000..139c9f7 --- /dev/null +++ b/sample/windows/commport.h @@ -0,0 +1,124 @@ +/** + * @file serial_interface_windows.h + * @author LDRobot (support@ldrobot.com) + * @brief Win32 serial port App + * @version 0.1 + * @date 2021-10-28 + * + * @copyright Copyright (c) 2021 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once +#include + +#include +#include +#include +#include + +struct PortInfo { + std::string name; + std::string description; + std::string pid; + std::string vid; +}; + +enum class BaudRate { + Baud1200 = 1200, + Baud2400 = 2400, + Baud4800 = 4800, + Baud9600 = 9600, + Baud19200 = 19200, + Baud38400 = 38400, + Baud57600 = 57600, + Baud115200 = 115200, + Baud230400 = 230400, + Unknonw = -1 +}; +enum class DataBits { + Data5 = 5, + Data6 = 6, + Data7 = 7, + Data8 = 8, + Unknonw = -1 +}; +enum class FlowControl { + NoFlowControl, + HardwareControl, + SoftwareControl, + Unknonw = -1 +}; +enum class Parity { + NoParity, + EvenParity, + OddParity, + SpaceParity, + MarkParity, + Unknonw = -1 +}; +enum class StopBits { OneStop = 0, TwoStop, OneAndHalfStop, Unknow }; + +struct PortParams { + std::string portName; + BaudRate baudrate = BaudRate::Baud115200; + Parity parity = Parity::NoParity; + DataBits dataBits = DataBits::Data8; + StopBits stopBits = StopBits::OneStop; + FlowControl flowControl = FlowControl::NoFlowControl; +}; + +class CommPort { + public: + CommPort(); + ~CommPort(); + + static bool availablePorts(std::vector &availabelPortInfo); + bool open(std::string port_name); + bool close(); + bool write(const char *tx_buf, uint32_t tx_buf_len); + int readAll(); + long long rxLength() { return mRxCounter; } + long long txLength() { return mTxCounter; } + void clearRxLength(void) { mRxCounter = 0; } + bool isOpen() { return mIsOpened; } + void setBufferSize(size_t size) { mMaxBuffSize = size; } + void setCommErrorCallback(std::function callback) { + commErrorHandle = callback; + } + void setReadCallback( + std::function callback) { + readCallback = callback; + } + + void setPortParams(PortParams params); + PortParams currPortParams(void); + + private: + bool mIsOpened; + HANDLE mComHandle; + std::thread *mRxThread; + static void rxThreadProc(CommPort *pClass); + size_t mByteToRead; + long long mRxCounter; + long long mTxCounter; + size_t mMaxBuffSize; + OVERLAPPED mOverlappedSend; + OVERLAPPED mOverlappedRecv; + std::atomic mRxThreadRunFlag; + + std::function commErrorHandle; + std::function readCallback; + + PortParams portParams; +}; + +/********************* (C) COPYRIGHT LD Robot *******END OF FILE ********/ \ No newline at end of file diff --git a/sample/windows/ldlidar_driver_win.cpp b/sample/windows/ldlidar_driver_win.cpp new file mode 100644 index 0000000..a428cde --- /dev/null +++ b/sample/windows/ldlidar_driver_win.cpp @@ -0,0 +1,205 @@ +/** + * @file ldlidar_driver.cpp + * @author LDRobot (support@ldrobot.com) + * @brief ldlidar sdk interface + * This code is only applicable to LDROBOT LiDAR products + * sold by Shenzhen LDROBOT Co., LTD + * @version 0.1 + * @date 2021-05-12 + * + * @copyright Copyright (c) 2022 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "ldlidar_driver_win.h" + +namespace ldlidar { + +bool LDLidarDriverWinInterface::is_ok_ = false; + +LDLidarDriverWinInterface::LDLidarDriverWinInterface() : + sdk_pack_version_(LDLiDAR_SDK_VERSION_NUMBER), + is_start_flag_(false), + comm_pkg_(new LiPkg()), + comm_port_handle_(new CommPort()) { + + last_pubdata_times_ = std::chrono::steady_clock::now(); +} + +LDLidarDriverWinInterface::~LDLidarDriverWinInterface() { + if (comm_pkg_ != nullptr) { + delete comm_pkg_; + } + + if (comm_port_handle_ != nullptr) { + delete comm_port_handle_; + } +} + +std::string LDLidarDriverWinInterface::GetLidarSdkVersionNumber(void) { + return sdk_pack_version_; +} + +bool LDLidarDriverWinInterface::Start(LDType product_name, + std::string& serial_port_name, + PortParams& port_params) { + + if (is_start_flag_) { + return true; + } + + if (serial_port_name.empty()) { + LOG_ERROR("input is empty.",""); + return false; + } + + if (register_get_timestamp_handle_ == nullptr) { + LOG_ERROR("get timestamp fuctional is not register.",""); + return false; + } + + comm_pkg_->ClearDataProcessStatus(); + comm_pkg_->RegisterTimestampGetFunctional(register_get_timestamp_handle_); + comm_pkg_->SetProductType(product_name); + + // Win32 + // 设置串口参数 + comm_port_handle_->setPortParams(port_params); + // 设置串口接收回调函数 + comm_port_handle_->setReadCallback(std::bind( + &LiPkg::CommReadCallback, comm_pkg_, std::placeholders::_1, std::placeholders::_2)); + // 打开串口 + if (!comm_port_handle_->open(serial_port_name)) { + LOG_ERROR("serial is not open:%s", serial_port_name.c_str()); + return false; + } + + is_start_flag_ = true; + + SetIsOkStatus(true); + + return true; +} + +bool LDLidarDriverWinInterface::Stop(void) { + if (!is_start_flag_) { + return true; + } + + SetIsOkStatus(false); + + comm_port_handle_->close(); + + is_start_flag_ = false; + + return true; +} + +void LDLidarDriverWinInterface::EnableFilterAlgorithnmProcess(bool is_enable) { + comm_pkg_->SetNoiseFilter(is_enable); +} + +bool LDLidarDriverWinInterface::WaitLidarCommConnect(int64_t timeout) { + auto last_time = std::chrono::steady_clock::now(); + + bool is_recvflag = false; + do { + if (comm_pkg_->GetLidarPowerOnCommStatus()) { + is_recvflag = true; + } + Sleep(1); + } while (!is_recvflag && (std::chrono::duration_cast( + std::chrono::steady_clock::now() - last_time).count() < timeout)); + + if (is_recvflag) { + last_pubdata_times_ = std::chrono::steady_clock::now(); + SetIsOkStatus(true); + return true; + } else { + SetIsOkStatus(false); + return false; + } +} + +LidarStatus LDLidarDriverWinInterface::GetLaserScanData(Points2D& dst, int64_t timeout) { + if (!is_start_flag_) { + return LidarStatus::STOP; + } + + LidarStatus status = comm_pkg_->GetLidarStatus(); + if (LidarStatus::NORMAL == status) { + if (comm_pkg_->GetLaserScanData(dst)) { + last_pubdata_times_ = std::chrono::steady_clock::now(); + return LidarStatus::NORMAL; + } + + if (std::chrono::duration_cast( + std::chrono::steady_clock::now() - last_pubdata_times_).count() > timeout) { + return LidarStatus::DATA_TIME_OUT; + } else { + return LidarStatus::DATA_WAIT; + } + } else { + last_pubdata_times_ = std::chrono::steady_clock::now(); + return status; + } +} + +LidarStatus LDLidarDriverWinInterface::GetLaserScanData(LaserScan& dst, int64_t timeout) { + if (!is_start_flag_) { + return LidarStatus::STOP; + } + + LidarStatus status = comm_pkg_->GetLidarStatus(); + if (LidarStatus::NORMAL == status) { + Points2D recvpcd; + if (comm_pkg_->GetLaserScanData(recvpcd)) { + last_pubdata_times_ = std::chrono::steady_clock::now(); + dst.stamp = recvpcd.front().stamp; + dst.points = recvpcd; + return LidarStatus::NORMAL; + } + + if (std::chrono::duration_cast( + std::chrono::steady_clock::now() - last_pubdata_times_).count() > timeout) { + return LidarStatus::DATA_TIME_OUT; + } else { + return LidarStatus::DATA_WAIT; + } + } else { + last_pubdata_times_ = std::chrono::steady_clock::now(); + return status; + } +} + +bool LDLidarDriverWinInterface::GetLidarScanFreq(double& spin_hz) { + if (!is_start_flag_) { + return false; + } + spin_hz = comm_pkg_->GetSpeed(); + return true; +} + +void LDLidarDriverWinInterface::RegisterGetTimestampFunctional(std::function get_timestamp_handle) { + register_get_timestamp_handle_ = get_timestamp_handle; +} + +uint8_t LDLidarDriverWinInterface::GetLidarErrorCode(void) { + if (!is_start_flag_) { + return LIDAR_NO_ERROR; + } + + uint8_t errcode = comm_pkg_->GetLidarErrorCode(); + return errcode; +} + +} // namespace ldlidar +/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF + * FILE ********/ \ No newline at end of file diff --git a/sample/windows/ldlidar_driver_win.h b/sample/windows/ldlidar_driver_win.h new file mode 100644 index 0000000..46b579a --- /dev/null +++ b/sample/windows/ldlidar_driver_win.h @@ -0,0 +1,129 @@ +/** + * @file ldlidar_driver.h + * @author LDRobot (support@ldrobot.com) + * @brief ldlidar sdk interface + * This code is only applicable to LDROBOT LiDAR LD14 + * products sold by Shenzhen LDROBOT Co., LTD + * @version 0.1 + * @date 2021-05-12 + * + * @copyright Copyright (c) 2022 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef __LDLIDAR_DRIVER_SDK_WIN_INTERFACE_H__ +#define __LDLIDAR_DRIVER_SDK_WIN_INTERFACE_H__ + +#include + +#include "ldlidar_driver/lipkg.h" +#include "ldlidar_driver/log_module.h" +#include "commport.h" + +namespace ldlidar { + +class LDLidarDriverWinInterface { +public: + LDLidarDriverWinInterface(); + + ~LDLidarDriverWinInterface(); + + std::string GetLidarSdkVersionNumber(void); + + /** + * @brief start lidar device handle node + * @param product_name + * ldlidar product type: ldlidar::LDType, value: + * - ldlidar::LDType::NOVER + * - ldlidar::LDType::LD_14 + * .... + * - else definition in "ldlidar_driver/include/ldlidar_datatype.h" + * @param serial_port_name + * serial device system path, eg: "/dev/ttyUSB0" + * @param serial_baudrate + * serial communication baudrate value(> 0), unit is bit/s. + * @retval value is true, start is success; + * value is false, start is failed. + */ + bool Start(LDType product_name, + std::string& serial_port_name, + PortParams& port_params); + + bool Stop(void); + + void EnableFilterAlgorithnmProcess(bool is_enable); + + /** + * @brief Whether the connection of the communication channel is normal after the lidar is powered on + * @param[in] + * *@param timeout: Wait timeout, in milliseconds + * @retval if times >= 1000, return false, communication connection is fail; + * if "times < 1000", return ture, communication connection is successful. + */ + bool WaitLidarCommConnect(int64_t timeout = 1000); + + /** + * @brief get lidar laser scan point cloud data + * @param [output] + * *@param dst: type is ldlidar::Point2D, value is laser scan point cloud data + * @param [in] + * *@param timeout: Wait timeout, in milliseconds + * @retval value is ldlidar::LidarStatus Enum Type, definition in "include/ldlidar_datatype.h", value is: + * ldlidar::LidarStatus::NORMAL // 雷达正常 + * lldlidar::LidarStatus::ERROR // 雷达异常错误 + * .... + */ + LidarStatus GetLaserScanData(Points2D& dst, int64_t timeout = 1000); + + LidarStatus GetLaserScanData(LaserScan& dst, int64_t timeout = 1000); + + /** + * @brief get lidar scan frequence + * @param [output] + * *@param spin_hz: value is lidar scan frequence, unit is Hz + * @retval value is true, get sucess; + */ + bool GetLidarScanFreq(double& spin_hz); + + /** + * @brief register get timestamp handle functional. + * @param [input] + * *@param get_timestamp_handle: type is `uint64_t (*)(void)`, value is pointer get timestamp fuction. + * @retval none + */ + void RegisterGetTimestampFunctional(std::function get_timestamp_handle); + + /** + * @brief When the lidar is in an error state, get the error code fed back by the lidar + * @param none + * @retval errcode + */ + uint8_t GetLidarErrorCode(void); + + static bool IsOk() { return is_ok_; } + + static void SetIsOkStatus(bool status) { is_ok_ = status;} + +private: + std::string sdk_pack_version_; + static bool is_ok_; + bool is_start_flag_; + LiPkg* comm_pkg_; + CommPort* comm_port_handle_; + + std::function register_get_timestamp_handle_; + std::chrono::steady_clock::time_point last_pubdata_times_; +}; + +} // namespace ldlidar + +#endif // __LDLIDAR_DRIVER_NODE_H__ +/********************* (C) COPYRIGHT SHENZHEN LDROBOT CO., LTD *******END OF + * FILE ********/ \ No newline at end of file diff --git a/sample/windows/windemo.cpp b/sample/windows/windemo.cpp new file mode 100644 index 0000000..d8dab7b --- /dev/null +++ b/sample/windows/windemo.cpp @@ -0,0 +1,181 @@ +/** + * @file main.cpp + * @author LDRobot (support@ldrobot.com) + * @brief main process App + * This code is only applicable to LDROBOT LiDAR LD00 LD03 LD08 LD14 + * products sold by Shenzhen LDROBOT Co., LTD + * @version 1.0 + * @date 2023-2-20 + * + * @copyright Copyright (c) 2021 SHENZHEN LDROBOT CO., LTD. All rights + * reserved. + * Licensed under the MIT License (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License in the file LICENSE + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "ldlidar_driver_win.h" + +uint64_t GetTimestamp(void) { + std::chrono::time_point tp = + std::chrono::time_point_cast(std::chrono::system_clock::now()); + auto tmp = std::chrono::duration_cast(tp.time_since_epoch()); + return ((uint64_t)tmp.count()); +} + +int main(int argc, char **argv) { + + struct lidar_inf_struct { + uint8_t index; + std::string type_name; + ldlidar::LDType type_number; + uint32_t baudrate; + }; + + const int inf_array_size = 3; + lidar_inf_struct inf_array[inf_array_size] = { + {0, "LDLiDAR LD06", ldlidar::LDType::LD_06, 230400}, + {1, "LDLiDAR LD14", ldlidar::LDType::LD_14, 115200}, + {2, "LDLiDAR LD19", ldlidar::LDType::LD_19, 230400} + }; + + printf("The SDK support ldlidar product:\n"); + for (auto inf_base : inf_array) { + printf("index:[%d] --- %s\n", inf_base.index, inf_base.type_name.c_str()); + } + uint8_t product_index; + printf("\nplease select product and input index value:\n"); + scanf_s("%d", &product_index); + if ((product_index < 0) || (product_index >= inf_array_size)) { + return -1; + } + + PortParams pp; + pp.baudrate = (BaudRate)inf_array[product_index].baudrate; + ldlidar::LDType lidar_type_number = inf_array[product_index].type_number; + + std::vector info; + CommPort::availablePorts(info); // get serial port device info + printf("\nAvailable port:\n\n"); + int port_index = 0; + for (auto p : info) { + printf("index:[%d] %s, %s,\n", port_index++, p.name.c_str(), p.description.c_str()); + } + + printf("\nplease select port and input index value:\n"); + scanf_s("%d", &port_index); + if (port_index > info.size()) { + return -1; + } + + ldlidar::LDLidarDriverWinInterface* ldlidar_drv = new ldlidar::LDLidarDriverWinInterface(); + + LOG_INFO_LITE("LDLiDAR SDK Pack Version is %s", ldlidar_drv->GetLidarSdkVersionNumber().c_str()); + + ldlidar_drv->RegisterGetTimestampFunctional(std::bind(&GetTimestamp)); + + ldlidar_drv->EnableFilterAlgorithnmProcess(true); + + if (ldlidar_drv->Start(lidar_type_number, info[port_index].name, pp)) { + LOG_INFO_LITE("ldlidar node start is success",""); + } else { + LOG_ERROR_LITE("ldlidar node start is fail",""); + exit(EXIT_FAILURE); + } + + if (ldlidar_drv->WaitLidarCommConnect(3500)) { + LOG_INFO_LITE("ldlidar communication is normal.",""); + } else { + LOG_ERROR_LITE("ldlidar communication is abnormal.",""); + ldlidar_drv->Stop(); + } + + ldlidar::Points2D laser_scan_points; + while (ldlidar::LDLidarDriverWinInterface::IsOk()) { + + switch (ldlidar_drv->GetLaserScanData(laser_scan_points, 1500)){ + case ldlidar::LidarStatus::NORMAL: { + double lidar_scan_freq = 0; + ldlidar_drv->GetLidarScanFreq(lidar_scan_freq); + LOG_INFO_LITE("speed(Hz):%f, size:%d,stamp_begin:%lu, stamp_end:%lu", + lidar_scan_freq, laser_scan_points.size(), laser_scan_points.front().stamp, laser_scan_points.back().stamp); + // output 2d point cloud data +#if 0 + for (auto point : laser_scan_points) { + LOG_INFO_LITE("stamp(ns):%lu,angle:%f,distance(mm):%d,intensity:%d", + point.stamp, point.angle, point.distance, point.intensity); + } +#endif + break; + } + case ldlidar::LidarStatus::DATA_TIME_OUT: { + LOG_ERROR_LITE("point cloud data publish time out, please check your lidar device.",""); + ldlidar_drv->Stop(); + break; + } + case ldlidar::LidarStatus::DATA_WAIT: { + break; + } + default: + break; + } + + Sleep(166); // sleep 166ms , 6hz + } + + ldlidar_drv->Stop(); + + delete ldlidar_drv; + ldlidar_drv = nullptr; + +#if 0 + CommPort cp; + + std::vector info; + + + CommPort::availablePorts(info); + + + PortParams pp; + pp.baudrate = (BaudRate)921600; + + cp.setPortParams(pp); + + printf("available port:\n\n"); + int n = 0; + for (auto p : info) + { + printf("[%d] %s, %s,\n", n++, p.name.c_str(), p.description.c_str()); + } + + printf("\nplease select port:\n"); + + scanf_s("%d", &n); + + if (n > info.size()) + { + return -1; + } + + + // cp.setReadCallback(); + + cp.open(info[n].name); + + printf("set address\n"); + + + while (1); + + cp.close(); +#endif + + + system("pause"); + return 0; +} \ No newline at end of file diff --git a/src/ldlidar_driver/ldlidar_driver.cpp b/src/ldlidar_driver/ldlidar_driver.cpp index 5fa6aa0..3040b86 100644 --- a/src/ldlidar_driver/ldlidar_driver.cpp +++ b/src/ldlidar_driver/ldlidar_driver.cpp @@ -24,7 +24,7 @@ namespace ldlidar { bool LDLidarDriver::is_ok_ = false; -LDLidarDriver::LDLidarDriver() : sdk_pack_version_("3.0.3"), +LDLidarDriver::LDLidarDriver() : sdk_pack_version_(LDLiDAR_SDK_VERSION_NUMBER), is_start_flag_(false), comm_pkg_(new LiPkg()), comm_serial_(new SerialInterfaceLinux()), diff --git a/src/ldlidar_driver/log_module.cpp b/src/ldlidar_driver/log_module.cpp index b1513c6..c547b3b 100644 --- a/src/ldlidar_driver/log_module.cpp +++ b/src/ldlidar_driver/log_module.cpp @@ -20,7 +20,7 @@ #include #include -#ifndef LINUX +#ifndef __linux__ #include #pragma comment(lib, "comsuppw.lib") #else @@ -79,8 +79,8 @@ LogModule::LogModule() { logInfo_.n_linenumber = -1; logInfo_.str_filename = ""; logInfo_.str_funcname = ""; -#ifndef LINUX - p_realization = new LogOutputString(); +#ifndef __linux__ + p_realization_ = new LogOutputString(); #else p_realization_ = new LogPrint(); #endif @@ -181,7 +181,7 @@ void LogModule::LogPrintOriginData(const char* format,...) { } void LogModule::InitLock() { -#ifndef LINUX +#ifndef __linux__ InitializeCriticalSection(&mutex_lock_); #else pthread_mutex_init(&mutex_lock_,NULL); @@ -189,7 +189,7 @@ void LogModule::InitLock() { } void LogModule::RealseLock() { -#ifndef LINUX +#ifndef __linux__ DeleteCriticalSection(&mutex_lock_); #else pthread_mutex_unlock(&mutex_lock_); @@ -197,7 +197,7 @@ void LogModule::RealseLock() { } void LogModule::Lock() { -#ifndef LINUX +#ifndef __linux__ EnterCriticalSection(&mutex_lock_); #else pthread_mutex_lock(&mutex_lock_); @@ -205,7 +205,7 @@ void LogModule::Lock() { } void LogModule::UnLock() { -#ifndef LINUX +#ifndef __linux__ LeaveCriticalSection(&mutex_lock_); #else pthread_mutex_unlock(&mutex_lock_);