加入G6雷达
This commit is contained in:
parent
f7dfb79dbb
commit
b1faf25fa2
|
@ -0,0 +1,8 @@
|
||||||
|
echo '安装EAI G6雷达'
|
||||||
|
sudo cp ~/spark_noetic/doc/lidar_ydlidar_g6.txt /opt/lidar.txt
|
||||||
|
sudo chmod 755 ~/spark_noetic/src/spark_driver/lidar/ydlidar_g6/startup/initenv.sh
|
||||||
|
sudo ~/spark_noetic/src/spark_driver/lidar/ydlidar_g6/startup/initenv.sh
|
||||||
|
echo '安装完成'
|
||||||
|
echo '请重新拔插雷达的USB接口'
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1 @@
|
||||||
|
ydlidar_g6
|
22
onekey.sh
22
onekey.sh
|
@ -28,13 +28,18 @@ calibra_default="${filepath}/../.ros/camera_info"
|
||||||
|
|
||||||
calibration="calibration"
|
calibration="calibration"
|
||||||
color_block="color_block"
|
color_block="color_block"
|
||||||
|
BASEPATH=$(cd `dirname $0`; pwd)
|
||||||
TYPE_LIDAR=$(cat /opt/lidar.txt)
|
TYPE_LIDAR=$(cat /opt/lidar.txt)
|
||||||
echo ${TYPE_LIDAR}
|
echo ${TYPE_LIDAR}
|
||||||
if [[ "${TYPE_LIDAR}" == "ydlidar_g2" ]]; then
|
if [[ "${TYPE_LIDAR}" == "ydlidar_g6" ]]; then
|
||||||
|
LIDARTYPE="ydlidar_g6"
|
||||||
|
rm -f ${BASEPATH}/src/spark_driver/lidar/ydlidar_g6/CATKIN_IGNORE
|
||||||
|
elif [[ "${TYPE_LIDAR}" == "ydlidar_g2" ]]; then
|
||||||
LIDARTYPE="ydlidar_g2"
|
LIDARTYPE="ydlidar_g2"
|
||||||
|
touch ${BASEPATH}/src/spark_driver/lidar/ydlidar_g6/CATKIN_IGNORE
|
||||||
elif [[ "${TYPE_LIDAR}" == "3iroboticslidar2" ]]; then
|
elif [[ "${TYPE_LIDAR}" == "3iroboticslidar2" ]]; then
|
||||||
LIDARTYPE="3iroboticslidar2"
|
LIDARTYPE="3iroboticslidar2"
|
||||||
|
touch ${BASEPATH}/src/spark_driver/lidar/ydlidar_g6/CATKIN_IGNORE
|
||||||
else
|
else
|
||||||
echo "暂不支持的雷达:${TYPE_LIDAR},使用默认的杉川雷达运行"
|
echo "暂不支持的雷达:${TYPE_LIDAR},使用默认的杉川雷达运行"
|
||||||
LIDARTYPE="3iroboticslidar2"
|
LIDARTYPE="3iroboticslidar2"
|
||||||
|
@ -296,10 +301,14 @@ master_uri_setup(){
|
||||||
wlp1s_ip=`/sbin/ifconfig wlp1s0|grep 'inet '|awk '{print $2}'`
|
wlp1s_ip=`/sbin/ifconfig wlp1s0|grep 'inet '|awk '{print $2}'`
|
||||||
wlp2s_ip=`/sbin/ifconfig wlp2s0|grep 'inet '|awk '{print $2}'`
|
wlp2s_ip=`/sbin/ifconfig wlp2s0|grep 'inet '|awk '{print $2}'`
|
||||||
wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'`
|
wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'`
|
||||||
enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'`
|
enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'`
|
||||||
|
wlo1_ip=`/sbin/ifconfig wlo1|grep 'inet '|awk '{print $2}'`
|
||||||
if [ $eth_ip ]; then
|
if [ $eth_ip ]; then
|
||||||
echo -e "${Info}使用有线网络eth0"
|
echo -e "${Info}使用有线网络eth0"
|
||||||
local_ip=$eth_ip
|
local_ip=$eth_ip
|
||||||
|
elif [ $wlo1_ip ]; then
|
||||||
|
echo -e "${Info}使用无线网络wlo1"
|
||||||
|
local_ip=$wlo1
|
||||||
elif [ $wlp1s_ip ]; then
|
elif [ $wlp1s_ip ]; then
|
||||||
echo -e "${Info}使用无线网络wlp1s0"
|
echo -e "${Info}使用无线网络wlp1s0"
|
||||||
local_ip=$wlp1s_ip
|
local_ip=$wlp1s_ip
|
||||||
|
@ -900,11 +909,14 @@ qrcode_transfer_files(){
|
||||||
wlp1s_ip=`/sbin/ifconfig wlp1s0|grep 'inet '|awk '{print $2}'`
|
wlp1s_ip=`/sbin/ifconfig wlp1s0|grep 'inet '|awk '{print $2}'`
|
||||||
wlp2s_ip=`/sbin/ifconfig wlp2s0|grep 'inet '|awk '{print $2}'`
|
wlp2s_ip=`/sbin/ifconfig wlp2s0|grep 'inet '|awk '{print $2}'`
|
||||||
wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'`
|
wlan_ip=`/sbin/ifconfig wlan0|grep 'inet '|awk '{print $2}'`
|
||||||
enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'`
|
enp3s_ip=`/sbin/ifconfig enp3s0|grep 'inet '|awk '{print $2}'`
|
||||||
|
wlo1_ip=`/sbin/ifconfig wlo1|grep 'inet '|awk '{print $2}'`
|
||||||
if [ $wlp1s_ip ]; then
|
if [ $wlp1s_ip ]; then
|
||||||
echo -e "${Info}使用无线网络wlp1s0"
|
echo -e "${Info}使用无线网络wlp1s0"
|
||||||
net_interface="wlp1s0"
|
net_interface="wlp1s0"
|
||||||
|
elif [ $wlo1_ip ]; then
|
||||||
|
echo -e "${Info}使用无线网络wlo1"
|
||||||
|
net_interface="wlo1"
|
||||||
elif [ $wlp2s_ip ]; then
|
elif [ $wlp2s_ip ]; then
|
||||||
echo -e "${Info}使用无线网络wlp2s0"
|
echo -e "${Info}使用无线网络wlp2s0"
|
||||||
net_interface="wlp2s0"
|
net_interface="wlp2s0"
|
||||||
|
|
|
@ -24,6 +24,10 @@
|
||||||
<xacro:include filename="$(find ydlidar_g2)/urdf/ydlidar.urdf" />
|
<xacro:include filename="$(find ydlidar_g2)/urdf/ydlidar.urdf" />
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
|
<xacro:if value="${lidar == 'ydlidar_g6'}">
|
||||||
|
<xacro:include filename="$(find ydlidar_g2)/urdf/ydlidar.urdf" />
|
||||||
|
</xacro:if>
|
||||||
|
|
||||||
<xacro:if value="${lidar == '3iroboticslidar2'}">
|
<xacro:if value="${lidar == '3iroboticslidar2'}">
|
||||||
<xacro:include filename="$(find spark_description)/urdf/sensors/spark_lidar.urdf"/>
|
<xacro:include filename="$(find spark_description)/urdf/sensors/spark_lidar.urdf"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
|
@ -1,13 +1,13 @@
|
||||||
Panels:
|
Panels:
|
||||||
- Class: rviz/Displays
|
- Class: rviz/Displays
|
||||||
Help Height: 75
|
Help Height: 0
|
||||||
Name: Displays
|
Name: Displays
|
||||||
Property Tree Widget:
|
Property Tree Widget:
|
||||||
Expanded:
|
Expanded:
|
||||||
- /TF1/Frames1
|
- /TF1/Frames1
|
||||||
- /PointCloud21
|
- /LaserScan1
|
||||||
Splitter Ratio: 0.5
|
Splitter Ratio: 0.5
|
||||||
Tree Height: 75
|
Tree Height: 140
|
||||||
- Class: rviz/Selection
|
- Class: rviz/Selection
|
||||||
Name: Selection
|
Name: Selection
|
||||||
- Class: rviz/Tool Properties
|
- Class: rviz/Tool Properties
|
||||||
|
@ -16,7 +16,7 @@ Panels:
|
||||||
- /2D Nav Goal1
|
- /2D Nav Goal1
|
||||||
- /Publish Point1
|
- /Publish Point1
|
||||||
Name: Tool Properties
|
Name: Tool Properties
|
||||||
Splitter Ratio: 0.588679016
|
Splitter Ratio: 0.5886790156364441
|
||||||
- Class: rviz/Views
|
- Class: rviz/Views
|
||||||
Expanded:
|
Expanded:
|
||||||
- /Current View1
|
- /Current View1
|
||||||
|
@ -27,6 +27,8 @@ Panels:
|
||||||
Name: Time
|
Name: Time
|
||||||
SyncMode: 0
|
SyncMode: 0
|
||||||
SyncSource: Image
|
SyncSource: Image
|
||||||
|
Preferences:
|
||||||
|
PromptSaveOnExit: true
|
||||||
Toolbars:
|
Toolbars:
|
||||||
toolButtonStyle: 2
|
toolButtonStyle: 2
|
||||||
Visualization Manager:
|
Visualization Manager:
|
||||||
|
@ -38,7 +40,7 @@ Visualization Manager:
|
||||||
Color: 160; 160; 164
|
Color: 160; 160; 164
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Line Style:
|
Line Style:
|
||||||
Line Width: 0.0299999993
|
Line Width: 0.029999999329447746
|
||||||
Value: Lines
|
Value: Lines
|
||||||
Name: Grid
|
Name: Grid
|
||||||
Normal Cell Count: 0
|
Normal Cell Count: 0
|
||||||
|
@ -246,6 +248,7 @@ Visualization Manager:
|
||||||
Value: false
|
Value: false
|
||||||
spark_stack:
|
spark_stack:
|
||||||
Value: false
|
Value: false
|
||||||
|
Marker Alpha: 1
|
||||||
Marker Scale: 1
|
Marker Scale: 1
|
||||||
Name: TF
|
Name: TF
|
||||||
Show Arrows: true
|
Show Arrows: true
|
||||||
|
@ -321,8 +324,8 @@ Visualization Manager:
|
||||||
- Alpha: 1
|
- Alpha: 1
|
||||||
Autocompute Intensity Bounds: true
|
Autocompute Intensity Bounds: true
|
||||||
Autocompute Value Bounds:
|
Autocompute Value Bounds:
|
||||||
Max Value: 2.84632468
|
Max Value: 1.014625906944275
|
||||||
Min Value: -0.040540576
|
Min Value: 0.43132248520851135
|
||||||
Value: true
|
Value: true
|
||||||
Axis: Z
|
Axis: Z
|
||||||
Channel Name: intensity
|
Channel Name: intensity
|
||||||
|
@ -333,21 +336,47 @@ Visualization Manager:
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Invert Rainbow: false
|
Invert Rainbow: false
|
||||||
Max Color: 255; 255; 255
|
Max Color: 255; 255; 255
|
||||||
Max Intensity: 4096
|
|
||||||
Min Color: 0; 0; 0
|
Min Color: 0; 0; 0
|
||||||
Min Intensity: 0
|
|
||||||
Name: PointCloud2
|
Name: PointCloud2
|
||||||
Position Transformer: XYZ
|
Position Transformer: XYZ
|
||||||
Queue Size: 10
|
Queue Size: 10
|
||||||
Selectable: true
|
Selectable: true
|
||||||
Size (Pixels): 3
|
Size (Pixels): 3
|
||||||
Size (m): 0.00999999978
|
Size (m): 0.009999999776482582
|
||||||
Style: Flat Squares
|
Style: Flat Squares
|
||||||
Topic: /camera/depth/points
|
Topic: /camera/depth/points
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Use Fixed Frame: true
|
Use Fixed Frame: true
|
||||||
Use rainbow: true
|
Use rainbow: true
|
||||||
Value: true
|
Value: true
|
||||||
|
- Alpha: 1
|
||||||
|
Autocompute Intensity Bounds: true
|
||||||
|
Autocompute Value Bounds:
|
||||||
|
Max Value: 10
|
||||||
|
Min Value: -10
|
||||||
|
Value: true
|
||||||
|
Axis: Z
|
||||||
|
Channel Name: intensity
|
||||||
|
Class: rviz/LaserScan
|
||||||
|
Color: 255; 255; 255
|
||||||
|
Color Transformer: Intensity
|
||||||
|
Decay Time: 0
|
||||||
|
Enabled: true
|
||||||
|
Invert Rainbow: false
|
||||||
|
Max Color: 255; 255; 255
|
||||||
|
Min Color: 0; 0; 0
|
||||||
|
Name: LaserScan
|
||||||
|
Position Transformer: XYZ
|
||||||
|
Queue Size: 10
|
||||||
|
Selectable: true
|
||||||
|
Size (Pixels): 3
|
||||||
|
Size (m): 0.009999999776482582
|
||||||
|
Style: Flat Squares
|
||||||
|
Topic: /scan
|
||||||
|
Unreliable: false
|
||||||
|
Use Fixed Frame: true
|
||||||
|
Use rainbow: true
|
||||||
|
Value: true
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Global Options:
|
Global Options:
|
||||||
Background Color: 48; 48; 48
|
Background Color: 48; 48; 48
|
||||||
|
@ -363,7 +392,10 @@ Visualization Manager:
|
||||||
- Class: rviz/FocusCamera
|
- Class: rviz/FocusCamera
|
||||||
- Class: rviz/Measure
|
- Class: rviz/Measure
|
||||||
- Class: rviz/SetInitialPose
|
- Class: rviz/SetInitialPose
|
||||||
|
Theta std deviation: 0.2617993950843811
|
||||||
Topic: /initialpose
|
Topic: /initialpose
|
||||||
|
X std deviation: 0.5
|
||||||
|
Y std deviation: 0.5
|
||||||
- Class: rviz/SetGoal
|
- Class: rviz/SetGoal
|
||||||
Topic: /move_base_simple/goal
|
Topic: /move_base_simple/goal
|
||||||
- Class: rviz/PublishPoint
|
- Class: rviz/PublishPoint
|
||||||
|
@ -373,35 +405,35 @@ Visualization Manager:
|
||||||
Views:
|
Views:
|
||||||
Current:
|
Current:
|
||||||
Class: rviz/Orbit
|
Class: rviz/Orbit
|
||||||
Distance: 10
|
Distance: 3.62917423248291
|
||||||
Enable Stereo Rendering:
|
Enable Stereo Rendering:
|
||||||
Stereo Eye Separation: 0.0599999987
|
Stereo Eye Separation: 0.05999999865889549
|
||||||
Stereo Focal Distance: 1
|
Stereo Focal Distance: 1
|
||||||
Swap Stereo Eyes: false
|
Swap Stereo Eyes: false
|
||||||
Value: false
|
Value: false
|
||||||
|
Field of View: 0.7853981852531433
|
||||||
Focal Point:
|
Focal Point:
|
||||||
X: 0
|
X: 0
|
||||||
Y: 0
|
Y: 0
|
||||||
Z: 0
|
Z: 0
|
||||||
Focal Shape Fixed Size: true
|
Focal Shape Fixed Size: true
|
||||||
Focal Shape Size: 0.0500000007
|
Focal Shape Size: 0.05000000074505806
|
||||||
Invert Z Axis: false
|
Invert Z Axis: false
|
||||||
Name: Current View
|
Name: Current View
|
||||||
Near Clip Distance: 0.00999999978
|
Near Clip Distance: 0.009999999776482582
|
||||||
Pitch: 0.415398329
|
Pitch: 0.41539832949638367
|
||||||
Target Frame: <Fixed Frame>
|
Target Frame: <Fixed Frame>
|
||||||
Value: Orbit (rviz)
|
Yaw: 2.715397357940674
|
||||||
Yaw: 2.71539736
|
|
||||||
Saved: ~
|
Saved: ~
|
||||||
Window Geometry:
|
Window Geometry:
|
||||||
Displays:
|
Displays:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
Height: 576
|
Height: 536
|
||||||
Hide Left Dock: false
|
Hide Left Dock: false
|
||||||
Hide Right Dock: true
|
Hide Right Dock: true
|
||||||
Image:
|
Image:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
QMainWindow State: 000000ff00000000fd00000004000000000000016a000001b6fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000000d7000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650100000105000000d90000001600ffffff000000010000010f0000025efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bf0000003efc0100000002fb0000000800540069006d00650100000000000003bf0000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000024f000001b600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
QMainWindow State: 000000ff00000000fd00000004000000000000016a0000017afc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000000c9000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000010c000000ab0000001600ffffff000000010000010f0000025efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003b80000003efc0100000002fb0000000800540069006d00650100000000000003b8000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002480000017a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
Selection:
|
Selection:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
Time:
|
Time:
|
||||||
|
@ -410,6 +442,6 @@ Window Geometry:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
Views:
|
Views:
|
||||||
collapsed: true
|
collapsed: true
|
||||||
Width: 959
|
Width: 952
|
||||||
X: 65
|
X: 72
|
||||||
Y: 24
|
Y: 27
|
||||||
|
|
|
@ -0,0 +1,33 @@
|
||||||
|
# Compiled Object files
|
||||||
|
*.slo
|
||||||
|
*.lo
|
||||||
|
*.o
|
||||||
|
*.obj
|
||||||
|
|
||||||
|
# Precompiled Headers
|
||||||
|
*.gch
|
||||||
|
*.pch
|
||||||
|
|
||||||
|
# Compiled Dynamic libraries
|
||||||
|
*.so
|
||||||
|
*.dylib
|
||||||
|
*.dll
|
||||||
|
|
||||||
|
# Fortran module files
|
||||||
|
*.mod
|
||||||
|
*.smod
|
||||||
|
|
||||||
|
# Compiled Static libraries
|
||||||
|
*.lai
|
||||||
|
*.la
|
||||||
|
*.a
|
||||||
|
*.lib
|
||||||
|
|
||||||
|
# Executables
|
||||||
|
*.exe
|
||||||
|
*.out
|
||||||
|
*.app
|
||||||
|
|
||||||
|
# IDE
|
||||||
|
.vscode/*
|
||||||
|
CMakeLists.txt.*
|
|
@ -0,0 +1,224 @@
|
||||||
|
cmake_minimum_required(VERSION 2.8)
|
||||||
|
project(ydlidar_sdk C CXX)
|
||||||
|
|
||||||
|
#########################################################
|
||||||
|
# version
|
||||||
|
set(YDLIDAR_SDK_VERSION_MAJOR 1)
|
||||||
|
set(YDLIDAR_SDK_VERSION_MINOR 0)
|
||||||
|
set(YDLIDAR_SDK_VERSION_PATCH 3)
|
||||||
|
set(YDLIDAR_SDK_VERSION ${YDLIDAR_SDK_VERSION_MAJOR}.${YDLIDAR_SDK_VERSION_MINOR}.${YDLIDAR_SDK_VERSION_PATCH})
|
||||||
|
|
||||||
|
##########################################################
|
||||||
|
# Detect wordsize:
|
||||||
|
IF(CMAKE_SIZEOF_VOID_P EQUAL 8) # Size in bytes!
|
||||||
|
SET(CMAKE_MRPT_WORD_SIZE 64)
|
||||||
|
ELSE()
|
||||||
|
SET(CMAKE_MRPT_WORD_SIZE 32)
|
||||||
|
ENDIF()
|
||||||
|
##################################################
|
||||||
|
#c++ 11
|
||||||
|
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
||||||
|
|
||||||
|
##########################################################
|
||||||
|
# add -fPIC
|
||||||
|
add_compile_options(-fPIC)
|
||||||
|
#or
|
||||||
|
#set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||||
|
|
||||||
|
#####################################################
|
||||||
|
# add cmake module path
|
||||||
|
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
|
||||||
|
set(SDK_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||||
|
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||||
|
#############################################################################
|
||||||
|
# include cmake file
|
||||||
|
include(common/ydlidar_base)
|
||||||
|
include(install_package)
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
# Policy CMP0023 allows to mix old and new interfaces of target_link_libraries
|
||||||
|
if(COMMAND cmake_policy)
|
||||||
|
cmake_policy(SET CMP0003 NEW) # We don't want to mix relative and absolute paths in linker lib lists.
|
||||||
|
cmake_policy(SET CMP0005 NEW) # Escape definitions (-D) strings
|
||||||
|
if(POLICY CMP0053)
|
||||||
|
cmake_policy(SET CMP0053 OLD) # Simplify variable reference and escape sequence evaluation.
|
||||||
|
endif()
|
||||||
|
if(POLICY CMP0037)
|
||||||
|
cmake_policy(SET CMP0037 OLD) # Allow defining target "test"
|
||||||
|
endif()
|
||||||
|
if(POLICY CMP0043)
|
||||||
|
cmake_policy(SET CMP0043 OLD) # Ignore COMPILE_DEFINITIONS_<Config> properties.
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
# option
|
||||||
|
option( BUILD_SHARED_LIBS "Build shared libraries." OFF)
|
||||||
|
option( BUILD_EXAMPLES "Build Example." ON)
|
||||||
|
option( BUILD_CSHARP "Build CSharp." OFF)
|
||||||
|
option( BUILD_TEST "Build Test." ON)
|
||||||
|
|
||||||
|
############################################################################
|
||||||
|
# find package
|
||||||
|
FIND_PACKAGE(SWIG)
|
||||||
|
find_package(PythonInterp)
|
||||||
|
FIND_PACKAGE(PythonLibs)
|
||||||
|
find_package(GTest)
|
||||||
|
|
||||||
|
############################################################################
|
||||||
|
# include headers
|
||||||
|
include_directories(.)
|
||||||
|
include_directories(core)
|
||||||
|
include_directories(src)
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
# addd subdirectory
|
||||||
|
add_subdirectory(core)
|
||||||
|
add_subdirectory(src)
|
||||||
|
|
||||||
|
##############################
|
||||||
|
#build examples
|
||||||
|
if(BUILD_EXAMPLES)
|
||||||
|
add_subdirectory(samples)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
# PARSE libraries
|
||||||
|
include(common/ydlidar_parse)
|
||||||
|
include_directories(${SDK_INCS})
|
||||||
|
|
||||||
|
########################################################
|
||||||
|
## Create configure file for inclusion in library
|
||||||
|
configure_file("${CMAKE_CURRENT_SOURCE_DIR}/ydlidar_config.h.in"
|
||||||
|
"${CMAKE_CURRENT_BINARY_DIR}/ydlidar_config.h" )
|
||||||
|
set( GENERATED_HEADERS ${CMAKE_CURRENT_BINARY_DIR}/ydlidar_config.h )
|
||||||
|
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
SET(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR})
|
||||||
|
|
||||||
|
#############################################################################################
|
||||||
|
#shared library
|
||||||
|
if(BUILD_SHARED_LIBS)
|
||||||
|
ydlidar_add_library(${PROJECT_NAME} SHARED ${SDK_SOURCES} ${SDK_HEADERS} ${GENERATED_HEADERS})
|
||||||
|
else()
|
||||||
|
ydlidar_add_library(${PROJECT_NAME} STATIC ${SDK_SOURCES} ${SDK_HEADERS} ${GENERATED_HEADERS})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
target_link_libraries(${PROJECT_NAME} ${SDK_LIBS})
|
||||||
|
target_include_directories(${PROJECT_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src)
|
||||||
|
|
||||||
|
#############################################################################################
|
||||||
|
#static library
|
||||||
|
#ydlidar_add_library(${PROJECT_NAME}_static STATIC ${SDK_SOURCES} ${SDK_HEADERS} ${GENERATED_HEADERS})
|
||||||
|
#SET_TARGET_PROPERTIES(${PROJECT_NAME}_static PROPERTIES OUTPUT_NAME "${PROJECT_NAME}")
|
||||||
|
#SET_TARGET_PROPERTIES(${PROJECT_NAME} PROPERTIES CLEAN_DIRECT_OUTPUT 1)
|
||||||
|
#SET_TARGET_PROPERTIES(${PROJECT_NAME}_static PROPERTIES CLEAN_DIRECT_OUTPUT 1)
|
||||||
|
|
||||||
|
#target_link_libraries(${PROJECT_NAME}_static ${SDK_LIBS})
|
||||||
|
#target_include_directories(${PROJECT_NAME}_static PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src)
|
||||||
|
|
||||||
|
|
||||||
|
############################################################################
|
||||||
|
# enable test
|
||||||
|
enable_testing()
|
||||||
|
|
||||||
|
############################################################################
|
||||||
|
# build ydlidar sdk python version
|
||||||
|
if(${SWIG_FOUND} AND ${PYTHONLIBS_FOUND})
|
||||||
|
message(STATUS "build python API....")
|
||||||
|
include_directories(python)
|
||||||
|
add_subdirectory(python)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
##############################################
|
||||||
|
# build ydlidar sdk c#
|
||||||
|
if(WIN32)
|
||||||
|
if(BUILD_CSHARP)
|
||||||
|
message(STATUS "build csharp API....")
|
||||||
|
include_directories(csharp)
|
||||||
|
add_subdirectory(csharp)
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
###############################################################################
|
||||||
|
# test
|
||||||
|
if(GTEST_FOUND AND BUILD_TEST)
|
||||||
|
message(STATUS "build test is ON.....")
|
||||||
|
include_directories(test)
|
||||||
|
add_subdirectory(test)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
###############################################################################
|
||||||
|
# append path
|
||||||
|
list(APPEND SDK_INCS ${CMAKE_INSTALL_PREFIX}/include/src
|
||||||
|
${CMAKE_INSTALL_PREFIX}/include)
|
||||||
|
|
||||||
|
|
||||||
|
###############################################################################
|
||||||
|
# install package
|
||||||
|
string(TOUPPER ${PROJECT_NAME} PROJECT_PKG_NAME)
|
||||||
|
install_package(
|
||||||
|
PKG_NAME ${PROJECT_PKG_NAME}
|
||||||
|
LIB_NAME ${PROJECT_NAME}
|
||||||
|
VERSION ${YDLIDAR_SDK_VERSION}
|
||||||
|
INSTALL_HEADERS ${SDK_HEADERS}
|
||||||
|
INSTALL_GENERATED_HEADERS ${GENERATED_HEADERS}
|
||||||
|
DESTINATION ${CMAKE_INSTALL_PREFIX}/include
|
||||||
|
INCLUDE_DIRS ${SDK_INCS}
|
||||||
|
LINK_LIBS ${SDK_LIBS}
|
||||||
|
)
|
||||||
|
#########################################################################################
|
||||||
|
# install doc
|
||||||
|
install(DIRECTORY cmake/ DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_PKG_NAME})
|
||||||
|
install(FILES LICENSE.txt README.md DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_PKG_NAME}/)
|
||||||
|
install(DIRECTORY doc DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_PKG_NAME})
|
||||||
|
IF (WIN32)
|
||||||
|
ELSE()
|
||||||
|
INSTALL(PROGRAMS startup/initenv.sh DESTINATION startup)
|
||||||
|
ENDIF()
|
||||||
|
|
||||||
|
include_directories(${CMAKE_BINARY_DIR} )
|
||||||
|
|
||||||
|
##################################################################################
|
||||||
|
# make an uninstall target
|
||||||
|
include(${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in)
|
||||||
|
add_custom_target(uninstall
|
||||||
|
COMMAND "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake")
|
||||||
|
|
||||||
|
|
||||||
|
########################################################
|
||||||
|
### make package or cpack -C CPackConfig.cmake
|
||||||
|
# packaging
|
||||||
|
#
|
||||||
|
# Important to having packaging at end of cmake file.
|
||||||
|
#
|
||||||
|
set(CPACK_PACKAGE_NAME ${PROJECT_NAME}-${YDLIDAR_SDK_VERSION})
|
||||||
|
set(CPACK_PACKAGE_VERSION ${YDLIDAR_SDK_VERSION})
|
||||||
|
set(CPACK_PACKAGE_CONTACT ${package-contact})
|
||||||
|
set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS OFF) # TODO: review packaging for linux boards
|
||||||
|
set(CPACK_DEBIAN_PACKAGE_SECTION "devel")
|
||||||
|
set(CPACK_DEBIAN_PACKAGE_PRIORITY "optional")
|
||||||
|
set(CPACK_DEBIAN_PACKAGE_DESCRIPTION "YDLIDAR SDK.")
|
||||||
|
set(CPACK_DEBIAN_PACKAGE_MAINTAINER "Tony Yang")
|
||||||
|
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${YDLIDAR_SDK_VERSION}")
|
||||||
|
set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${YDLIDAR_SDK_VERSION}")
|
||||||
|
set(CPACK_SOURCE_GENERATOR "ZIP;TBZ2")
|
||||||
|
set(CPACK_PACKAGING_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
|
||||||
|
set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
|
||||||
|
set(CPACK_SET_DESTDIR true)
|
||||||
|
set(CPACK_OUTPUT_FILE_PREFIX ${CMAKE_CURRENT_BINARY_DIR})
|
||||||
|
if ("${CMAKE_SYSTEM}" MATCHES "Linux")
|
||||||
|
set(CPACK_GENERATOR "TBZ2")
|
||||||
|
find_program(DPKG_PROGRAM dpkg)
|
||||||
|
if (EXISTS ${DPKG_PROGRAM})
|
||||||
|
list (APPEND CPACK_GENERATOR "DEB")
|
||||||
|
endif()
|
||||||
|
else()
|
||||||
|
set(CPACK_GENERATOR "ZIP")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
include(CPack)
|
||||||
|
|
||||||
|
# Summary
|
||||||
|
include(cmake/script_show_final_summary.cmake REQUIRED)
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,250 @@
|
||||||
|
The following portions of the YDLIDAR’s YDlidar SDK (“Software” referred to in the terms below) are made available to you under the terms of the MIT License provided below.
|
||||||
|
|
||||||
|
YDLidar-SDK
|
||||||
|
├── cmake
|
||||||
|
│ ├── cmake_uninstall.cmake.in
|
||||||
|
│ ├── common
|
||||||
|
│ │ ├── ydlidar_base.cmake
|
||||||
|
│ │ └── ydlidar_parse.cmake
|
||||||
|
│ ├── FindPackage.cmake.in
|
||||||
|
│ ├── install_package.cmake
|
||||||
|
│ ├── PackageConfig.cmake.in
|
||||||
|
│ ├── PackageConfigVersion.cmake.in
|
||||||
|
│ └── PkgConfig.pc.in
|
||||||
|
├── CMakeLists.txt
|
||||||
|
├── core
|
||||||
|
│ ├── base
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── datatype.h
|
||||||
|
│ │ ├── locker.h
|
||||||
|
│ │ ├── thread.h
|
||||||
|
│ │ ├── timer.cpp
|
||||||
|
│ │ ├── timer.h
|
||||||
|
│ │ ├── typedef.h
|
||||||
|
│ │ ├── utils.h
|
||||||
|
│ │ ├── v8stdint.h
|
||||||
|
│ │ └── ydlidar.h
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── common
|
||||||
|
│ │ ├── ChannelDevice.h
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── DriverInterface.h
|
||||||
|
│ │ ├── ydlidar_datatype.h
|
||||||
|
│ │ ├── ydlidar_def.cpp
|
||||||
|
│ │ ├── ydlidar_def.h
|
||||||
|
│ │ ├── ydlidar_help.h
|
||||||
|
│ │ └── ydlidar_protocol.h
|
||||||
|
│ ├── math
|
||||||
|
│ │ ├── angles.h
|
||||||
|
│ │ └── CMakeLists.txt
|
||||||
|
│ ├── network
|
||||||
|
│ │ ├── ActiveSocket.cpp
|
||||||
|
│ │ ├── ActiveSocket.h
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── PassiveSocket.cpp
|
||||||
|
│ │ ├── PassiveSocket.h
|
||||||
|
│ │ ├── SimpleSocket.cpp
|
||||||
|
│ │ ├── SimpleSocket.h
|
||||||
|
│ │ └── StatTimer.h
|
||||||
|
│ └── serial
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── common.h
|
||||||
|
│ ├── impl
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── unix
|
||||||
|
│ │ │ ├── CMakeLists.txt
|
||||||
|
│ │ │ ├── list_ports_linux.cpp
|
||||||
|
│ │ │ ├── lock.c
|
||||||
|
│ │ │ ├── lock.h
|
||||||
|
│ │ │ ├── unix.h
|
||||||
|
│ │ │ ├── unix_serial.cpp
|
||||||
|
│ │ │ └── unix_serial.h
|
||||||
|
│ │ └── windows
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── list_ports_win.cpp
|
||||||
|
│ │ ├── win.h
|
||||||
|
│ │ ├── win_serial.cpp
|
||||||
|
│ │ └── win_serial.h
|
||||||
|
│ ├── serial.cpp
|
||||||
|
│ └── serial.h
|
||||||
|
├── csharp
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── examples
|
||||||
|
│ │ └── CMakeLists.txt
|
||||||
|
│ └── ydlidar_sdk.i
|
||||||
|
├── LICENSE.txt
|
||||||
|
├── python
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── examples
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── etlidar_test.py
|
||||||
|
│ │ ├── plot_tof_test.py
|
||||||
|
│ │ ├── plot_ydlidar_test.py
|
||||||
|
│ │ ├── test.py
|
||||||
|
│ │ ├── tof_test.py
|
||||||
|
│ │ └── ydlidar_test.py
|
||||||
|
│ ├── numpy.i
|
||||||
|
│ ├── test
|
||||||
|
│ │ └── pytest.py
|
||||||
|
│ ├── ydlidar_numpy.i
|
||||||
|
│ └── ydlidar_sdk.i
|
||||||
|
├── README.md
|
||||||
|
├── samples
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── etlidar_test.cpp
|
||||||
|
│ ├── lidar_c_api_test.c
|
||||||
|
│ ├── tof_test.cpp
|
||||||
|
│ └── ydlidar_test.cpp
|
||||||
|
├── setup.py
|
||||||
|
├── src
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── CYdLidar.cpp
|
||||||
|
│ ├── CYdLidar.h
|
||||||
|
│ ├── ETLidarDriver.cpp
|
||||||
|
│ ├── ETLidarDriver.h
|
||||||
|
│ ├── ydlidar_driver.cpp
|
||||||
|
│ ├── ydlidar_driver.h
|
||||||
|
│ ├── ydlidar_sdk.cpp
|
||||||
|
│ └── ydlidar_sdk.h
|
||||||
|
├── startup
|
||||||
|
│ └── initenv.sh
|
||||||
|
└── ydlidar_config.h.in
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
-------------------------------------------------------------
|
||||||
|
The MIT License (MIT)
|
||||||
|
|
||||||
|
Copyright (c) 2019-2020 EAIBOT. All rights reserved.
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
SOFTWARE.
|
||||||
|
===============================================================
|
||||||
|
|
||||||
|
serial
|
||||||
|
├── CMakeLists.txt
|
||||||
|
├── common.h
|
||||||
|
├── impl
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── unix
|
||||||
|
│ │ ├── CMakeLists.txt
|
||||||
|
│ │ ├── list_ports_linux.cpp
|
||||||
|
│ │ ├── lock.c
|
||||||
|
│ │ ├── lock.h
|
||||||
|
│ │ ├── unix.h
|
||||||
|
│ │ ├── unix_serial.cpp
|
||||||
|
│ │ └── unix_serial.h
|
||||||
|
│ └── windows
|
||||||
|
│ ├── CMakeLists.txt
|
||||||
|
│ ├── list_ports_win.cpp
|
||||||
|
│ ├── win.h
|
||||||
|
│ ├── win_serial.cpp
|
||||||
|
│ └── win_serial.h
|
||||||
|
├── serial.cpp
|
||||||
|
└── serial.h
|
||||||
|
|
||||||
|
YDLIDAR’s YDLidar-SDK uses modified libraries of serial (https://github.com/wjwwood/serial), which is licensed under MIT license. A copy of the MIT license is provided below and is also available at https://raw.githubusercontent.com/wjwwood/serial/master/README.md.
|
||||||
|
|
||||||
|
The MIT License
|
||||||
|
|
||||||
|
Copyright (c) 2012 William Woodall, John Harrison
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||||
|
===============================================================
|
||||||
|
|
||||||
|
For the math\angles.h component:
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2008, Willow Garage, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of the Willow Garage nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*********************************************************************/
|
||||||
|
|
||||||
|
===============================================================
|
||||||
|
For the network library:
|
||||||
|
|
||||||
|
/* Copyright (c) 2006 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,74 @@
|
||||||
|
![YDLIDAR](doc/images/YDLidar.jpg "YDLIDAR")
|
||||||
|
|
||||||
|
# Table of Contents
|
||||||
|
|
||||||
|
1. [Introduction](#introduction)
|
||||||
|
- [Prerequisites](#prerequisites)
|
||||||
|
- [Supported Languages](#supported-languages)
|
||||||
|
2. [YDLidar SDK Communication Protocol](#ydlidar-sdk-communication-protocol)
|
||||||
|
3. [Architecture](#architecture)
|
||||||
|
4. [Installation](#installation)
|
||||||
|
5. [Documents](#documents)
|
||||||
|
6. [Support](#support)
|
||||||
|
7. [Contact EAI](#contact-eai)
|
||||||
|
|
||||||
|
# Introduction
|
||||||
|
|
||||||
|
YDLidar SDK is the software development kit designed for all YDLIDAR products. It is developed based on C/C++ following YDLidar SDK Communication Protocol, and provides easy-to-use C/C++, Python, C# style API. With YDLidar SDK, users can quickly connect to YDLidar products and receive Laser scan data.
|
||||||
|
|
||||||
|
YDLidar SDK consists of YDLidar SDK communication protocol, YDLidar SDK core, YDLidar SDK API, Linux/windows samples, and Python demo.
|
||||||
|
|
||||||
|
### Prerequisites
|
||||||
|
* Linux
|
||||||
|
* Windows 7/10, Visual Studio 2015/2017
|
||||||
|
* C++11 compiler
|
||||||
|
|
||||||
|
### Supported Languages
|
||||||
|
* C / C++
|
||||||
|
* Python
|
||||||
|
* C#
|
||||||
|
|
||||||
|
## YDLidar SDK Communication Protocol
|
||||||
|
YDLidar SDK communication protocol opens to all users. It is the communication protocol between user programs and YDLIDAR products. The protocol consists of control commands and data format. Please refer to the [YDLidar SDK Communication Protocol](doc/YDLidar-SDK-Communication-Protocol.md) for detailed information.
|
||||||
|
|
||||||
|
## Architecture
|
||||||
|
|
||||||
|
YDLidar SDK provides the implementation of control commands and Laser scan data transmission, as well as the C/C++,Python API. The basic structure of YDLidar SDK is shown as below:
|
||||||
|
|
||||||
|
![YDLidar SDK Architecture](doc/images/sdk_architecture.png)
|
||||||
|
|
||||||
|
Serial or network is used for communication between YDLidar SDK and LiDAR sensors. Please refer to the YDLidar SDK Communication Protocol for further information. LaserScan supports Laser Scan Data transmission, while Command handler receives and sends control commands. And the C++ API is based on Command and LaserScan Hander.
|
||||||
|
|
||||||
|
The YDLidar LiDAR sensors can be connected to host directly by serial or through the YDLidar Adapter board. YDLidar SDK supports both connection methods. When LiDAR units are connected to host directly by Serial, the host will establish communication with each LiDAR unit individually. And if the LiDAR units connect to host through Adapter board, then the host only communicates with the YDLidar Adapter board while the Adapter Board communicates with each LiDAR unit.
|
||||||
|
|
||||||
|
## Installation
|
||||||
|
|
||||||
|
* [Fork and then Clone YDLidar-SDK's GitHub code](https://github.com/YDLIDAR/YDLidar-SDK)
|
||||||
|
|
||||||
|
* [Build and Install](doc/howto/how_to_build_and_install.md) - This step is required
|
||||||
|
|
||||||
|
## Documents
|
||||||
|
* [LiDAR Dataset](doc/Dataset.md): All you need to know about LiDAR Models.
|
||||||
|
|
||||||
|
* [SDK FlowChart](doc/Diagram.md): Development flowchart.
|
||||||
|
|
||||||
|
* [YDLIDAR SDK API for Developers](doc/YDLIDAR_SDK_API_for_Developers.md): All you need to know about YDLiDAR-SDK API
|
||||||
|
|
||||||
|
* [YDLIDAR SDK Communication Protocol](doc/YDLidar-SDK-Communication-Protocol.md): All you need to know about YDLiDAR-SDK Communication Protocol.
|
||||||
|
|
||||||
|
* [HowTo](doc/howto/README.md): Brief technical solutions to common problems that developers face during the installation and use of the YDLidar-SDk
|
||||||
|
|
||||||
|
* [Tutorials](doc/Tutorials.md): Quick Tutorials
|
||||||
|
|
||||||
|
* [FAQs](doc/FAQs/README.md)
|
||||||
|
|
||||||
|
## Support
|
||||||
|
|
||||||
|
You can get support from YDLidar with the following methods:
|
||||||
|
* Send email to support@ydlidar.com with a clear description of your problem and your setup
|
||||||
|
* Github Issues
|
||||||
|
|
||||||
|
## Contact EAI
|
||||||
|
![Development Path](doc/images/EAI.png)
|
||||||
|
|
||||||
|
If you have any extra questions, please feel free to [contact us](http://www.ydlidar.cn/cn/contact)
|
Binary file not shown.
|
@ -0,0 +1,10 @@
|
||||||
|
|
||||||
|
SET( @PACKAGE_PKG_NAME@_LIBRARIES @PACKAGE_LINK_LIBS@ CACHE INTERNAL "@PACKAGE_PKG_NAME@ libraries" FORCE )
|
||||||
|
SET( @PACKAGE_PKG_NAME@_INCLUDE_DIRS @PACKAGE_INCLUDE_DIRS@ CACHE INTERNAL "@PACKAGE_PKG_NAME@ include directories" FORCE )
|
||||||
|
SET( @PACKAGE_PKG_NAME@_LIBRARY_DIRS @PACKAGE_LINK_DIRS@ CACHE INTERNAL "@PACKAGE_PKG_NAME@ library directories" FORCE )
|
||||||
|
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_LIBRARIES )
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_LIBRARY_DIRS )
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_INCLUDE_DIRS )
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,24 @@
|
||||||
|
SET( @PACKAGE_PKG_NAME@_LIBRARIES "@PACKAGE_LINK_LIBS@" CACHE INTERNAL "@PACKAGE_PKG_NAME@ libraries" FORCE )
|
||||||
|
SET( @PACKAGE_PKG_NAME@_INCLUDE_DIRS @PACKAGE_INCLUDE_DIRS@ CACHE INTERNAL "@PACKAGE_PKG_NAME@ include directories" FORCE )
|
||||||
|
SET( @PACKAGE_PKG_NAME@_LIBRARY_DIRS @PACKAGE_LINK_DIRS@ CACHE INTERNAL "@PACKAGE_PKG_NAME@ library directories" FORCE )
|
||||||
|
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_LIBRARIES )
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_LIBRARY_DIRS )
|
||||||
|
mark_as_advanced( @PACKAGE_PKG_NAME@_INCLUDE_DIRS )
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
# Compute paths
|
||||||
|
get_filename_component( PACKAGE_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH )
|
||||||
|
|
||||||
|
# This file, when used for INSTALLED code, does not use Targets... sigh.
|
||||||
|
## Library dependencies (contains definitions for IMPORTED targets)
|
||||||
|
#if(NOT TARGET "@PACKAGE_PKG_NAME@_LIBRARIES" AND NOT "@PACKAGE_PKG_NAME@_BINARY_DIR")
|
||||||
|
# include( "${PACKAGE_CMAKE_DIR}/@PACKAGE_PKG_NAME@Targets.cmake" )
|
||||||
|
# include( "${PACKAGE_CMAKE_DIR}/@PACKAGE_PKG_NAME@ConfigVersion.cmake" )
|
||||||
|
#endif()
|
||||||
|
|
||||||
|
#SET(@PACKAGE_PKG_NAME@_LIBRARIES @PACKAGE_LIBRARIES@)
|
||||||
|
#SET(@PACKAGE_PKG_NAME@_LIBRARY @PACKAGE_LIBRARY@)
|
||||||
|
#SET(@PACKAGE_PKG_NAME@_INCLUDE_DIRS @PACKAGE_INCLUDE_DIRS@)
|
||||||
|
#SET(@PACKAGE_PKG_NAME@_LINK_DIRS @PACKAGE_LINK_DIRS@)
|
|
@ -0,0 +1,17 @@
|
||||||
|
set(PACKAGE_VERSION "@PACKAGE_VERSION@")
|
||||||
|
|
||||||
|
# Check build type is valid
|
||||||
|
if( "System:${CMAKE_SYSTEM_NAME},Android:${ANDROID},iOS:${IOS}" STREQUAL
|
||||||
|
"System:@CMAKE_SYSTEM_NAME@,Android:@ANDROID@,iOS:@IOS@" )
|
||||||
|
# Check whether the requested PACKAGE_FIND_VERSION is compatible
|
||||||
|
if("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}")
|
||||||
|
set(PACKAGE_VERSION_COMPATIBLE FALSE)
|
||||||
|
else()
|
||||||
|
set(PACKAGE_VERSION_COMPATIBLE TRUE)
|
||||||
|
if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}")
|
||||||
|
set(PACKAGE_VERSION_EXACT TRUE)
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
else()
|
||||||
|
set(PACKAGE_VERSION_COMPATIBLE FALSE)
|
||||||
|
endif()
|
|
@ -0,0 +1,11 @@
|
||||||
|
prefix=@CMAKE_INSTALL_PREFIX@
|
||||||
|
exec_prefix=${prefix}
|
||||||
|
libdir=${exec_prefix}/lib
|
||||||
|
includedir=${prefix}/include
|
||||||
|
|
||||||
|
Name: @PACKAGE_PKG_NAME@
|
||||||
|
Description: @PACKAGE_DESCRIPTION@
|
||||||
|
Version: @PACKAGE_VERSION@
|
||||||
|
Cflags: @PACKAGE_CFLAGS@
|
||||||
|
Libs: -L${libdir} @PACKAGE_LIBS@ @PACKAGE_LIB_LINK@
|
||||||
|
|
|
@ -0,0 +1,26 @@
|
||||||
|
## A simple uninstall script.
|
||||||
|
## Alternatively UNIX users can run/sudo `xargs rm < install_manifest.txt` in the build directory.
|
||||||
|
|
||||||
|
set(unfile ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake)
|
||||||
|
file(WRITE ${unfile} "IF(NOT EXISTS \"install_manifest.txt\")\n")
|
||||||
|
file(APPEND ${unfile} "MESSAGE(\"FATAL_ERROR Cannot find \\\"install manifest\\\": install_manifest.txt\")\n")
|
||||||
|
file(APPEND ${unfile} "ENDIF(NOT EXISTS \"install_manifest.txt\")\n")
|
||||||
|
file(APPEND ${unfile} "FILE(READ \"install_manifest.txt\" files)\n")
|
||||||
|
file(APPEND ${unfile} "STRING(REGEX REPLACE \"\\n\" \";\" files \"\${files}\")\n")
|
||||||
|
file(APPEND ${unfile} "FOREACH(file \${files})\n")
|
||||||
|
file(APPEND ${unfile} " MESSAGE(STATUS \"Uninstalling \\\"\${file}\\\"\")\n")
|
||||||
|
file(APPEND ${unfile} " IF(EXISTS \"\${file}\")\n")
|
||||||
|
file(APPEND ${unfile} " EXEC_PROGRAM(\n")
|
||||||
|
file(APPEND ${unfile} " \"\${CMAKE_COMMAND}\" ARGS \"-E remove \\\"\${file}\\\"\"\n")
|
||||||
|
file(APPEND ${unfile} " OUTPUT_VARIABLE rm_out\n")
|
||||||
|
file(APPEND ${unfile} " RETURN_VALUE rm_retval\n")
|
||||||
|
file(APPEND ${unfile} " )\n")
|
||||||
|
file(APPEND ${unfile} " IF(\"\${rm_retval}\" STREQUAL 0\)\n")
|
||||||
|
file(APPEND ${unfile} " ELSE(\"\${rm_retval}\" STREQUAL 0\)\n")
|
||||||
|
file(APPEND ${unfile} " MESSAGE(FATAL_ERROR \"Problem when removing \\\"\${file}\\\"\")\n")
|
||||||
|
file(APPEND ${unfile} " ENDIF(\"\${rm_retval}\" STREQUAL 0)\n")
|
||||||
|
file(APPEND ${unfile} " ELSE(EXISTS \"\${file}\")\n")
|
||||||
|
file(APPEND ${unfile} " MESSAGE(STATUS \"File \\\"\${file}\\\" does not exist. \")\n")
|
||||||
|
file(APPEND ${unfile} " ENDIF(EXISTS \"\${file}\")\n")
|
||||||
|
file(APPEND ${unfile} "ENDFOREACH(file)\n")
|
||||||
|
|
|
@ -0,0 +1,388 @@
|
||||||
|
|
||||||
|
include(CMakeParseArguments)
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_parse_function_args
|
||||||
|
#
|
||||||
|
# This function simplifies usage of the cmake_parse_arguments module.
|
||||||
|
# It is intended to be called by other functions.
|
||||||
|
#
|
||||||
|
# Usage:
|
||||||
|
# ydlidar_parse_function_args(
|
||||||
|
# NAME <name>
|
||||||
|
# [ OPTIONS <list> ]
|
||||||
|
# [ ONE_VALUE <list> ]
|
||||||
|
# [ MULTI_VALUE <list> ]
|
||||||
|
# REQUIRED <list>
|
||||||
|
# ARGN <ARGN>)
|
||||||
|
#
|
||||||
|
# Input:
|
||||||
|
# NAME : the name of the calling function
|
||||||
|
# OPTIONS : boolean flags
|
||||||
|
# ONE_VALUE : single value variables
|
||||||
|
# MULTI_VALUE : multi value variables
|
||||||
|
# REQUIRED : required arguments
|
||||||
|
# ARGN : the function input arguments, typically ${ARGN}
|
||||||
|
#
|
||||||
|
# Output:
|
||||||
|
# The function arguments corresponding to the following are set:
|
||||||
|
# ${OPTIONS}, ${ONE_VALUE}, ${MULTI_VALUE}
|
||||||
|
#
|
||||||
|
# Example:
|
||||||
|
# function test()
|
||||||
|
# ydlidar_parse_function_args(
|
||||||
|
# NAME TEST
|
||||||
|
# ONE_VALUE NAME
|
||||||
|
# MULTI_VALUE LIST
|
||||||
|
# REQUIRED NAME LIST
|
||||||
|
# ARGN ${ARGN})
|
||||||
|
# message(STATUS "name: ${NAME}")
|
||||||
|
# message(STATUS "list: ${LIST}")
|
||||||
|
# endfunction()
|
||||||
|
#
|
||||||
|
# test(NAME "hello" LIST a b c)
|
||||||
|
#
|
||||||
|
# OUTPUT:
|
||||||
|
# name: hello
|
||||||
|
# list: a b c
|
||||||
|
#
|
||||||
|
function(ydlidar_parse_function_args)
|
||||||
|
cmake_parse_arguments(IN "" "NAME" "OPTIONS;ONE_VALUE;MULTI_VALUE;REQUIRED;ARGN" "${ARGN}")
|
||||||
|
cmake_parse_arguments(OUT "${IN_OPTIONS}" "${IN_ONE_VALUE}" "${IN_MULTI_VALUE}" "${IN_ARGN}")
|
||||||
|
if (OUT_UNPARSED_ARGUMENTS)
|
||||||
|
message(FATAL_ERROR "${IN_NAME}: unparsed ${OUT_UNPARSED_ARGUMENTS}")
|
||||||
|
endif()
|
||||||
|
foreach(arg ${IN_REQUIRED})
|
||||||
|
if (NOT OUT_${arg})
|
||||||
|
if (NOT "${OUT_${arg}}" STREQUAL "0")
|
||||||
|
message(FATAL_ERROR "${IN_NAME} requires argument ${arg}\nARGN: ${IN_ARGN}")
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
foreach(arg ${IN_OPTIONS} ${IN_ONE_VALUE} ${IN_MULTI_VALUE})
|
||||||
|
set(${arg} ${OUT_${arg}} PARENT_SCOPE)
|
||||||
|
endforeach()
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
|
||||||
|
macro( add_to_ydlidar_include_dirs )
|
||||||
|
foreach( dir ${ARGN} )
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_INCLUDE_DIRS "${dir}" )
|
||||||
|
endforeach()
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
macro( add_to_ydlidar_libraries )
|
||||||
|
foreach( lib ${ARGN} )
|
||||||
|
# Process targets correctly
|
||||||
|
if (TARGET ${lib})
|
||||||
|
# If the library is NOT imported, ie is in this project, we
|
||||||
|
# want to depend on it directly rather than through its path
|
||||||
|
get_target_property(is_lib_imported ${lib} IMPORTED)
|
||||||
|
if (NOT ${is_lib_imported})
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES "${lib}" )
|
||||||
|
else()
|
||||||
|
# For imported targets, we just want to depend on the library directly
|
||||||
|
get_target_property(libpath ${lib} LOCATION)
|
||||||
|
if (libpath)
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES "${libpath}" )
|
||||||
|
# This shouldn't really happen, but let's cover our bases.
|
||||||
|
else()
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES "${lib}" )
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
else() # Just add the direct path/flag to the list
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES "${lib}" )
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
macro( add_to_ydlidar_sources )
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
file(RELATIVE_PATH _relPath "${CMAKE_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||||
|
else()
|
||||||
|
file(RELATIVE_PATH _relPath "${SDK_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||||
|
endif()
|
||||||
|
foreach(_src ${ARGN})
|
||||||
|
if(_relPath)
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_SOURCES "${_relPath}/${_src}" )
|
||||||
|
else()
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_SOURCES "${_src}" )
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
macro( add_to_ydlidar_headers )
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
file(RELATIVE_PATH _relPath "${CMAKE_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||||
|
else()
|
||||||
|
file(RELATIVE_PATH _relPath "${SDK_SOURCE_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||||
|
endif()
|
||||||
|
foreach(_hdr ${ARGN})
|
||||||
|
if(_relPath)
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_HEADERS "${_relPath}/${_hdr}" )
|
||||||
|
else()
|
||||||
|
set_property( GLOBAL APPEND PROPERTY YDLIDAR_HEADERS "${_hdr}" )
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
macro( ydlidar_set_compile_flags file flags )
|
||||||
|
set_property( GLOBAL APPEND PROPERTY COMPILER_OPTS_SOURCES "${file}" )
|
||||||
|
set_property( GLOBAL APPEND PROPERTY COMPILER_OPTS_FLAGS "${flags}" )
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
macro(subdirlist result curdir)
|
||||||
|
file(GLOB children RELATIVE ${curdir} ${curdir}/*)
|
||||||
|
set(dirlist "")
|
||||||
|
foreach(child ${children})
|
||||||
|
if( NOT child STREQUAL "CMakeFiles" )
|
||||||
|
if(IS_DIRECTORY ${curdir}/${child})
|
||||||
|
set(dirlist ${dirlist} ${child})
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
set(${result} ${dirlist})
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
macro(aux_include_directory dir result )
|
||||||
|
set(curdir ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
if(NOT (${dir} STREQUAL ".") )
|
||||||
|
set(curdir ${dir})
|
||||||
|
endif()
|
||||||
|
FILE(GLOB INC_LIST "${curdir}/*.h")
|
||||||
|
FILE(GLOB PRV_INC_LIST "${curdir}/*.hpp")
|
||||||
|
set(INCS "")
|
||||||
|
foreach(child ${INC_LIST})
|
||||||
|
string(REPLACE "${curdir}/" "" child_LIST ${child})
|
||||||
|
list(APPEND INCS ${child_LIST})
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
foreach(prvchild ${PRV_INC_LIST})
|
||||||
|
string(REPLACE "${curdir}/" "" prvchild_LIST ${prvchild})
|
||||||
|
list(APPEND INCS ${prvchild_LIST})
|
||||||
|
endforeach()
|
||||||
|
set(${result} ${INCS})
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
macro(aux_src_directory dir result )
|
||||||
|
set(curdir ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
if(NOT (${dir} STREQUAL ".") )
|
||||||
|
set(curdir ${dir})
|
||||||
|
endif()
|
||||||
|
FILE(GLOB INC_LIST "${curdir}/*.c")
|
||||||
|
FILE(GLOB PRV_INC_LIST "${curdir}/*.cpp")
|
||||||
|
FILE(GLOB TPP_INC_LIST "${curdir}/*.tpp")
|
||||||
|
set(INCS "")
|
||||||
|
foreach(child ${INC_LIST})
|
||||||
|
string(REPLACE "${curdir}/" "" child_LIST ${child})
|
||||||
|
list(APPEND INCS ${child_LIST})
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
foreach(prvchild ${PRV_INC_LIST})
|
||||||
|
string(REPLACE "${curdir}/" "" prvchild_LIST ${prvchild})
|
||||||
|
list(APPEND INCS ${prvchild_LIST})
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
|
||||||
|
foreach(tppchild ${TPP_INC_LIST})
|
||||||
|
string(REPLACE "${curdir}/" "" tppchild_LIST ${tppchild})
|
||||||
|
list(APPEND INCS ${tppchild_LIST})
|
||||||
|
endforeach()
|
||||||
|
set(${result} ${INCS})
|
||||||
|
endmacro()
|
||||||
|
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_strip_optimization
|
||||||
|
#
|
||||||
|
function(ydlidar_strip_optimization name)
|
||||||
|
set(_compile_flags)
|
||||||
|
separate_arguments(_args UNIX_COMMAND ${ARGN})
|
||||||
|
foreach(_flag ${_args})
|
||||||
|
if(NOT "${_flag}" MATCHES "^-O")
|
||||||
|
set(_compile_flags "${_compile_flags} ${_flag}")
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
string(STRIP "${_compile_flags}" _compile_flags)
|
||||||
|
set(${name} "${_compile_flags}" PARENT_SCOPE)
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_join
|
||||||
|
#
|
||||||
|
# This function joins a list with a given separator. If list is not
|
||||||
|
# passed, or is sent "", this will return the empty string.
|
||||||
|
#
|
||||||
|
# Usage:
|
||||||
|
# ydlidar_join(OUT ${OUT} [ LIST ${LIST} ] GLUE ${GLUE})
|
||||||
|
#
|
||||||
|
# Input:
|
||||||
|
# LIST : list to join
|
||||||
|
# GLUE : separator to use
|
||||||
|
#
|
||||||
|
# Output:
|
||||||
|
# OUT : joined list
|
||||||
|
#
|
||||||
|
# Example:
|
||||||
|
# ydlidar_join(OUT test_join LIST a b c GLUE ";")
|
||||||
|
# test_join would then be:
|
||||||
|
# "a;b;c"
|
||||||
|
#
|
||||||
|
function(ydlidar_join)
|
||||||
|
ydlidar_parse_function_args(
|
||||||
|
NAME ydlidar_join
|
||||||
|
ONE_VALUE OUT GLUE
|
||||||
|
MULTI_VALUE LIST
|
||||||
|
REQUIRED GLUE OUT
|
||||||
|
ARGN ${ARGN})
|
||||||
|
string (REPLACE ";" "${GLUE}" _TMP_STR "${LIST}")
|
||||||
|
set(${OUT} ${_TMP_STR} PARENT_SCOPE)
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
function(ydlidar_add_module)
|
||||||
|
|
||||||
|
ydlidar_parse_function_args(
|
||||||
|
NAME ydlidar_add_module
|
||||||
|
ONE_VALUE MODULE
|
||||||
|
MULTI_VALUE COMPILE_FLAGS LINK_FLAGS SRCS INCLUDES DEPENDS
|
||||||
|
OPTIONS EXTERNAL
|
||||||
|
REQUIRED MODULE
|
||||||
|
ARGN ${ARGN})
|
||||||
|
|
||||||
|
|
||||||
|
ydlidar_add_library(${MODULE} STATIC EXCLUDE_FROM_ALL ${SRCS})
|
||||||
|
|
||||||
|
# Pass variable to the parent ydlidar_add_module.
|
||||||
|
set(_no_optimization_for_target ${_no_optimization_for_target} PARENT_SCOPE)
|
||||||
|
|
||||||
|
if(COMPILE_FLAGS)
|
||||||
|
target_compile_options(${MODULE} PRIVATE ${COMPILE_FLAGS})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(INCLUDES)
|
||||||
|
target_include_directories(${MODULE} PRIVATE ${INCLUDES})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(DEPENDS)
|
||||||
|
add_dependencies(${MODULE} ${DEPENDS})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# join list variables to get ready to send to compiler
|
||||||
|
foreach(prop LINK_FLAGS)
|
||||||
|
if(${prop})
|
||||||
|
ydlidar_join(OUT ${prop} LIST ${${prop}} GLUE " ")
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
if(COMPILE_FLAGS AND ${_no_optimization_for_target})
|
||||||
|
ydlidar_strip_optimization(COMPILE_FLAGS ${COMPILE_FLAGS})
|
||||||
|
endif()
|
||||||
|
foreach (prop LINK_FLAGS )
|
||||||
|
if (${prop})
|
||||||
|
set_target_properties(${MODULE} PROPERTIES ${prop} ${${prop}})
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
set_property(GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES ${MODULE})
|
||||||
|
set_property(GLOBAL APPEND PROPERTY YDLIDAR_MODULE_PATHS ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_add_optimization_flags_for_target
|
||||||
|
#
|
||||||
|
set(all_posix_cmake_targets "" CACHE INTERNAL "All cmake targets for which optimization can be suppressed")
|
||||||
|
function(ydlidar_add_optimization_flags_for_target target)
|
||||||
|
set(_no_optimization_for_target FALSE)
|
||||||
|
# If the current CONFIG is posix_sitl_* then suppress optimization for certain targets.
|
||||||
|
foreach(_regexp $ENV{CORE_NO_OPTIMIZATION})
|
||||||
|
if("${target}" MATCHES "${_regexp}")
|
||||||
|
set(_no_optimization_for_target TRUE)
|
||||||
|
set(_matched_regexp "${_regexp}")
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
# Create a full list of targets that optimization can be suppressed for.
|
||||||
|
list(APPEND all_posix_cmake_targets ${target})
|
||||||
|
set(all_posix_cmake_targets ${all_posix_cmake_targets} CACHE INTERNAL "All cmake targets for which optimization can be suppressed")
|
||||||
|
if(NOT ${_no_optimization_for_target})
|
||||||
|
target_compile_options(${target} PRIVATE ${optimization_flags})
|
||||||
|
else()
|
||||||
|
message(STATUS "Disabling optimization for target '${target}' because it matches the regexp '${_matched_regexp}' in env var CORE_NO_OPTIMIZATION")
|
||||||
|
target_compile_options(${target} PRIVATE -O0)
|
||||||
|
endif()
|
||||||
|
# Pass variable to the parent ydlidar_add_library.
|
||||||
|
set(_no_optimization_for_target ${_no_optimization_for_target} PARENT_SCOPE)
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_add_executable
|
||||||
|
#
|
||||||
|
# Like add_executable but with optimization flag fixup.
|
||||||
|
#
|
||||||
|
function(ydlidar_add_executable target)
|
||||||
|
add_executable(${target} ${ARGN})
|
||||||
|
ydlidar_add_optimization_flags_for_target(${target})
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_add_library
|
||||||
|
#
|
||||||
|
# Like add_library but with optimization flag fixup.
|
||||||
|
#
|
||||||
|
function(ydlidar_add_library target)
|
||||||
|
add_library(${target} ${ARGN})
|
||||||
|
ydlidar_add_optimization_flags_for_target(${target})
|
||||||
|
|
||||||
|
# Pass variable to the parent ydlidar_add_module.
|
||||||
|
set(_no_optimization_for_target ${_no_optimization_for_target} PARENT_SCOPE)
|
||||||
|
|
||||||
|
set_property(GLOBAL APPEND PROPERTY YDLIDAR_LIBRARIES ${target})
|
||||||
|
set_property(GLOBAL APPEND PROPERTY YDLIDAR_MODULE_PATHS ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
|
||||||
|
endfunction()
|
||||||
|
|
||||||
|
|
||||||
|
#=============================================================================
|
||||||
|
#
|
||||||
|
# ydlidar_prebuild_targets
|
||||||
|
#
|
||||||
|
# This function generates os dependent targets
|
||||||
|
#
|
||||||
|
# Usage:
|
||||||
|
# ydlidar_prebuild_targets(
|
||||||
|
# OUT <out-list_of_targets>
|
||||||
|
# BOARD <in-string>
|
||||||
|
# )
|
||||||
|
#
|
||||||
|
# Input:
|
||||||
|
# BOARD : board
|
||||||
|
#
|
||||||
|
# Output:
|
||||||
|
# OUT : the target list
|
||||||
|
#
|
||||||
|
# Example:
|
||||||
|
# ydlidar_prebuild_targets(OUT target_list BOARD r16)
|
||||||
|
#
|
||||||
|
function(ydlidar_prebuild_targets)
|
||||||
|
ydlidar_parse_function_args(
|
||||||
|
NAME ydlidar_prebuild_targets
|
||||||
|
ONE_VALUE OUT BOARD
|
||||||
|
REQUIRED OUT
|
||||||
|
ARGN ${ARGN})
|
||||||
|
|
||||||
|
add_library(prebuild_targets INTERFACE)
|
||||||
|
#add_dependencies(prebuild_targets DEPENDS)
|
||||||
|
|
||||||
|
endfunction()
|
|
@ -0,0 +1,71 @@
|
||||||
|
|
||||||
|
include(common/ydlidar_base)
|
||||||
|
#############################################################################
|
||||||
|
# Setup libraries
|
||||||
|
|
||||||
|
get_property( INTERNAL_INC GLOBAL PROPERTY YDLIDAR_INCLUDE_DIRS )
|
||||||
|
get_property( INTERNAL_LIBS GLOBAL PROPERTY YDLIDAR_LIBRARIES )
|
||||||
|
get_property( SDK_SOURCES GLOBAL PROPERTY YDLIDAR_SOURCES )
|
||||||
|
get_property( SDK_HEADERS GLOBAL PROPERTY YDLIDAR_HEADERS )
|
||||||
|
|
||||||
|
|
||||||
|
# this is a horrible hack in order to set compiler flag properties to individual files
|
||||||
|
get_property( C_O_S GLOBAL PROPERTY COMPILER_OPTS_SOURCES )
|
||||||
|
get_property( C_O_F GLOBAL PROPERTY COMPILER_OPTS_FLAGS )
|
||||||
|
|
||||||
|
list(LENGTH C_O_S len_c_o_s )
|
||||||
|
math(EXPR len_c_o_s "${len_c_o_s} - 1" )
|
||||||
|
|
||||||
|
foreach(val RANGE ${len_c_o_s} )
|
||||||
|
list(GET C_O_S ${val} source )
|
||||||
|
list(GET C_O_F ${val} flag )
|
||||||
|
set_source_files_properties( ${source} PROPERTIES COMPILE_FLAGS ${flag} )
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
##########################################################################
|
||||||
|
|
||||||
|
include_directories(${CMAKE_SOURCE_DIR} ${CMAKE_BINARY_DIR} )
|
||||||
|
include_directories( ${LIB_INC_DIR} )
|
||||||
|
include_directories( ${INTERNAL_INC} )
|
||||||
|
|
||||||
|
|
||||||
|
##########################################################################
|
||||||
|
# ccache: a compiler, can speed up gcc compilation.
|
||||||
|
#
|
||||||
|
option(CCACHE "Use ccache if available" ON)
|
||||||
|
find_program(CCACHE_PROGRAM ccache)
|
||||||
|
if (CCACHE AND CCACHE_PROGRAM AND NOT DEFINED ENV{CCACHE_DISABLE})
|
||||||
|
set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE "${CCACHE_PROGRAM}")
|
||||||
|
else()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
##########################################################################
|
||||||
|
# generate compile command database
|
||||||
|
#
|
||||||
|
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||||
|
|
||||||
|
##########################################################################
|
||||||
|
# check required toolchain variables
|
||||||
|
#
|
||||||
|
# search for programs in the build host directories
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||||
|
# for libraries and headers in the target directories
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||||
|
SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
||||||
|
|
||||||
|
|
||||||
|
#############################################################################
|
||||||
|
|
||||||
|
set(SDK_LIBS
|
||||||
|
${INTERNAL_LIBS}
|
||||||
|
${LINK_LIBS}
|
||||||
|
CACHE STRING "SDK required libraries"
|
||||||
|
)
|
||||||
|
|
||||||
|
list( REMOVE_ITEM SDK_LIBS "debug" )
|
||||||
|
list( REMOVE_ITEM SDK_LIBS "optimized" )
|
||||||
|
|
||||||
|
set(SDK_INCS
|
||||||
|
${INTERNAL_INC}
|
||||||
|
${USER_INC}
|
||||||
|
CACHE STRING "SDK required incs" )
|
|
@ -0,0 +1,296 @@
|
||||||
|
################################################################################
|
||||||
|
# install_package.cmake - This function will install and "export" your library
|
||||||
|
# or files in such a way that they can be found using either CMake's
|
||||||
|
# "FindXXX.cmake" mechanism or with pkg-config. This makes your code boradly
|
||||||
|
# compatible with traditional unix best practices, and also easy to use from
|
||||||
|
# other CMake projets.
|
||||||
|
#
|
||||||
|
# This function will create and install a ${PACKAGE}.pc pkg-config file.
|
||||||
|
# Will also create a Find${PACKAGE}.cmake, which will in turn call.
|
||||||
|
|
||||||
|
#
|
||||||
|
# install_package - Takes a package name and the following optional named arguments:
|
||||||
|
# PKG_NAME <name of the package for pkg-config>, usually the same as ${PROJECT_NAME}
|
||||||
|
# LIB_NAME <name of a library to build, if any>
|
||||||
|
# VERSION <version>
|
||||||
|
# INSTALL_HEADERS <header files to install, if any>
|
||||||
|
# DESTINATION <directory to install headers>
|
||||||
|
# INCLUDE_DIRS <list of required include directories, if any>
|
||||||
|
# LINK_LIBS <list of required link libraries, if any >
|
||||||
|
# LINK_DIRS <list of required link directories, if any>
|
||||||
|
# CFLAGS <optional list of REQUIRED c flags>
|
||||||
|
# CXXFLAGS <optional list of REQUIRED c++ flags>
|
||||||
|
#
|
||||||
|
################################################################################
|
||||||
|
include(CMakeParseArguments)
|
||||||
|
|
||||||
|
get_filename_component(modules_dir ${CMAKE_CURRENT_LIST_FILE} PATH)
|
||||||
|
|
||||||
|
function(install_package)
|
||||||
|
set(PACKAGE_OPTIONS "")
|
||||||
|
set(PACKAGE_SINGLE_ARGS "")
|
||||||
|
set( PACKAGE_MULTI_ARGS
|
||||||
|
PKG_NAME
|
||||||
|
LIB_NAME
|
||||||
|
VERSION
|
||||||
|
DESCRIPTION
|
||||||
|
INSTALL_HEADERS
|
||||||
|
INSTALL_GENERATED_HEADERS
|
||||||
|
INSTALL_HEADER_DIRS
|
||||||
|
INSTALL_INCLUDE_DIR
|
||||||
|
DESTINATION
|
||||||
|
INCLUDE_DIRS
|
||||||
|
LINK_LIBS
|
||||||
|
LINK_DIRS
|
||||||
|
CFLAGS
|
||||||
|
CXXFLAGS
|
||||||
|
)
|
||||||
|
cmake_parse_arguments( PACKAGE
|
||||||
|
"${PACKAGE_OPTIONS}"
|
||||||
|
"${PACKAGE_SINGLE_ARGS}"
|
||||||
|
"${PACKAGE_MULTI_ARGS}"
|
||||||
|
"${ARGN}"
|
||||||
|
)
|
||||||
|
|
||||||
|
# Add package to CMake package registery for use from the build tree. RISKY.
|
||||||
|
option( EXPORT_${PROJECT_NAME}
|
||||||
|
"Should the ${PROJECT_NAME} package be exported for use by other software" OFF )
|
||||||
|
|
||||||
|
mark_as_advanced( EXPORT_${PROJECT_NAME} )
|
||||||
|
|
||||||
|
|
||||||
|
# clean things up
|
||||||
|
if( PACKAGE_LINK_DIRS )
|
||||||
|
list( REMOVE_DUPLICATES PACKAGE_LINK_DIRS )
|
||||||
|
endif()
|
||||||
|
if(PACKAGE_LINK_LIBS)
|
||||||
|
list( REMOVE_DUPLICATES PACKAGE_LINK_LIBS )
|
||||||
|
endif()
|
||||||
|
if( PACKAGE_INCLUDE_DIRS)
|
||||||
|
list( REMOVE_DUPLICATES PACKAGE_INCLUDE_DIRS )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# construct Cflags arguments for pkg-config file
|
||||||
|
set( PACKAGE_CFLAGS "${PACKAGE_CFLAGS} ${CMAKE_C_FLAGS}" )
|
||||||
|
foreach(var IN LISTS PACKAGE_INCLUDE_DIRS )
|
||||||
|
set( PACKAGE_CFLAGS "${PACKAGE_CFLAGS} -I${var}" )
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
# now construct Libs.private arguments
|
||||||
|
foreach(var IN LISTS PACKAGE_LINK_DIRS )
|
||||||
|
set( PACKAGE_LIBS "${PACKAGE_LIBS} -L${var}" )
|
||||||
|
endforeach()
|
||||||
|
foreach(var IN LISTS PACKAGE_LINK_LIBS )
|
||||||
|
if( EXISTS ${var} OR ${var} MATCHES "-framework*" )
|
||||||
|
set( PACKAGE_LIBS "${PACKAGE_LIBS} ${var}" )
|
||||||
|
else() # assume it's just a -l call??
|
||||||
|
set( PACKAGE_LIBS "${PACKAGE_LIBS} -l${var}" )
|
||||||
|
endif()
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
# add any CXX flags user has passed in
|
||||||
|
if( PACKAGE_CXXFLAGS )
|
||||||
|
set( PACKAGE_CFLAGS ${PACKAGE_CXXFLAGS} )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# In case we want to install.
|
||||||
|
if( NOT EXPORT_${PROJECT_NAME} )
|
||||||
|
# add "installed" library to list of required libraries to link against
|
||||||
|
if( PACKAGE_LIB_NAME )
|
||||||
|
if(POLICY CMP0026)
|
||||||
|
cmake_policy( SET CMP0026 OLD )
|
||||||
|
endif()
|
||||||
|
get_target_property( _target_library ${PACKAGE_LIB_NAME} LOCATION )
|
||||||
|
get_filename_component( _lib ${_target_library} NAME )
|
||||||
|
list( INSERT PACKAGE_LINK_LIBS 0 ${PACKAGE_LIB_NAME} )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if( PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
foreach(dir IN LISTS PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
install( DIRECTORY ${dir}
|
||||||
|
DESTINATION ${PACKAGE_DESTINATION}/include
|
||||||
|
FILES_MATCHING PATTERN "*.h|*.hxx|*.hpp"
|
||||||
|
)
|
||||||
|
endforeach()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# install header files
|
||||||
|
if( PACKAGE_INSTALL_HEADERS )
|
||||||
|
foreach(hdr IN LISTS PACKAGE_INSTALL_HEADERS )
|
||||||
|
get_filename_component( _fp ${hdr} ABSOLUTE )
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
file( RELATIVE_PATH _rpath ${CMAKE_SOURCE_DIR} ${_fp} )
|
||||||
|
else()
|
||||||
|
file( RELATIVE_PATH _rpath ${SDK_SOURCE_DIR} ${_fp} )
|
||||||
|
endif()
|
||||||
|
get_filename_component( _dir ${_rpath} DIRECTORY )
|
||||||
|
install( FILES ${_fp}
|
||||||
|
DESTINATION ${PACKAGE_DESTINATION}/${_dir} )
|
||||||
|
endforeach()
|
||||||
|
endif()
|
||||||
|
if( PACKAGE_INSTALL_GENERATED_HEADERS )
|
||||||
|
foreach(hdr IN LISTS PACKAGE_INSTALL_GENERATED_HEADERS )
|
||||||
|
get_filename_component( _fp ${hdr} ABSOLUTE )
|
||||||
|
file( RELATIVE_PATH _rpath ${CMAKE_BINARY_DIR} ${_fp} )
|
||||||
|
get_filename_component( _dir ${_rpath} DIRECTORY )
|
||||||
|
install( FILES ${_fp}
|
||||||
|
DESTINATION ${PACKAGE_DESTINATION}/${_dir} )
|
||||||
|
endforeach()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if( PACKAGE_INSTALL_INCLUDE_DIR )
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
install(DIRECTORY ${CMAKE_SOURCE_DIR}/include DESTINATION ${PACKAGE_DESTINATION} )
|
||||||
|
else()
|
||||||
|
install(DIRECTORY ${SDK_SOURCE_DIR}/include DESTINATION ${PACKAGE_DESTINATION} )
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# install library itself
|
||||||
|
if( PACKAGE_LIB_NAME )
|
||||||
|
install( FILES ${_target_library} DESTINATION ${CMAKE_INSTALL_PREFIX}/lib )
|
||||||
|
set( PACKAGE_LIB_LINK "-l${PACKAGE_LIB_NAME}" )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# build pkg-config file
|
||||||
|
if( PACKAGE_PKG_NAME )
|
||||||
|
configure_file( ${modules_dir}/PkgConfig.pc.in ${PACKAGE_PKG_NAME}.pc @ONLY )
|
||||||
|
|
||||||
|
# install pkg-config file for external projects to discover this library
|
||||||
|
install( FILES ${CMAKE_CURRENT_BINARY_DIR}/${PACKAGE_PKG_NAME}.pc
|
||||||
|
DESTINATION ${CMAKE_INSTALL_PREFIX}/lib/pkgconfig/ )
|
||||||
|
|
||||||
|
#######################################################
|
||||||
|
# Export library for easy inclusion from other cmake projects. APPEND allows
|
||||||
|
# call to function even as subdirectory of larger project.
|
||||||
|
FILE(REMOVE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake")
|
||||||
|
export( TARGETS ${LIBRARY_NAME}
|
||||||
|
APPEND FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake" )
|
||||||
|
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
# Version information. So find_package( XXX version ) will work.
|
||||||
|
configure_file( ${CMAKE_SOURCE_DIR}/cmake/PackageConfigVersion.cmake.in
|
||||||
|
"${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" @ONLY )
|
||||||
|
|
||||||
|
# Build tree config. So some folks can use the built package (e.g., any of our
|
||||||
|
# own examples or applcations in this project.
|
||||||
|
configure_file( ${CMAKE_SOURCE_DIR}/cmake/PackageConfig.cmake.in
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
else()
|
||||||
|
# Version information. So find_package( XXX version ) will work.
|
||||||
|
configure_file( ${SDK_SOURCE_DIR}/cmake/PackageConfigVersion.cmake.in
|
||||||
|
"${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" @ONLY )
|
||||||
|
|
||||||
|
# Build tree config. So some folks can use the built package (e.g., any of our
|
||||||
|
# own examples or applcations in this project.
|
||||||
|
configure_file( ${SDK_SOURCE_DIR}/cmake/PackageConfig.cmake.in
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
|
||||||
|
install(FILES
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake
|
||||||
|
DESTINATION
|
||||||
|
lib/cmake/${PROJECT_NAME})
|
||||||
|
|
||||||
|
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/Find${PACKAGE_PKG_NAME}.cmake
|
||||||
|
DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PACKAGE_PKG_NAME}/ )
|
||||||
|
|
||||||
|
|
||||||
|
# # Install tree config. NB we DO NOT use this. We install using brew or
|
||||||
|
# pkg-config.
|
||||||
|
# set( EXPORT_LIB_INC_DIR ${LIB_INC_DIR} )
|
||||||
|
# set( EXPORT_LIB_INC_DIR "\${PROJECT_CMAKE_DIR}/${REL_INCLUDE_DIR}" )
|
||||||
|
# configure_file( ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}Config.cmake.in
|
||||||
|
# ${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# In case we want to export.
|
||||||
|
elseif( EXPORT_${PROJECT_NAME} )
|
||||||
|
|
||||||
|
if( PACKAGE_LIB_NAME )
|
||||||
|
if(POLICY CMP0026)
|
||||||
|
cmake_policy( SET CMP0026 OLD )
|
||||||
|
endif()
|
||||||
|
get_target_property( _target_library ${PACKAGE_LIB_NAME} LOCATION )
|
||||||
|
list( INSERT PACKAGE_LINK_LIBS 0 ${_target_library} )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if( PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
foreach(dir IN LISTS PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
list( APPEND PACKAGE_INCLUDE_DIRS ${dir} )
|
||||||
|
endforeach()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
#if( PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
# foreach(dir IN LISTS PACKAGE_INSTALL_HEADER_DIRS )
|
||||||
|
# FILE( GLOB ${dir} "*.h" "*.hpp" )
|
||||||
|
# list( APPEND PACKAGE_INCLUDE_DIRS ${dir} )
|
||||||
|
# endforeach()
|
||||||
|
#endif()
|
||||||
|
|
||||||
|
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
list( APPEND PACKAGE_INCLUDE_DIRS ${CMAKE_SOURCE_DIR}
|
||||||
|
${CMAKE_BINARY_DIR} )
|
||||||
|
else()
|
||||||
|
list( APPEND PACKAGE_INCLUDE_DIRS ${SDK_SOURCE_DIR}
|
||||||
|
${CMAKE_BINARY_DIR} )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# install library itself
|
||||||
|
#if( PACKAGE_LIB_NAME )
|
||||||
|
# set( PACKAGE_LIB_LINK "-l${PACKAGE_LIB_NAME}" )
|
||||||
|
#endif()
|
||||||
|
#######################################################
|
||||||
|
# Export library for easy inclusion from other cmake projects. APPEND allows
|
||||||
|
# call to function even as subdirectory of larger project.
|
||||||
|
FILE(REMOVE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake")
|
||||||
|
export( TARGETS ${LIBRARY_NAME}
|
||||||
|
APPEND FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake" )
|
||||||
|
|
||||||
|
export( PACKAGE ${PROJECT_NAME} )
|
||||||
|
# install( EXPORT ${PROJECT_NAME}Targets DESTINATION ${CMAKECONFIG_INSTALL_DIR} )
|
||||||
|
# install(TARGETS ${LIBRARY_NAME}
|
||||||
|
# EXPORT ${PROJECT_NAME}Targets DESTINATION ${CMAKE_INSTALL_PREFIX}/lib
|
||||||
|
# )
|
||||||
|
|
||||||
|
if("${SDK_SOURCE_DIR}" STREQUAL "")
|
||||||
|
# Version information. So find_package( XXX version ) will work.
|
||||||
|
configure_file( ${CMAKE_SOURCE_DIR}/cmake/PackageConfigVersion.cmake.in
|
||||||
|
"${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" @ONLY )
|
||||||
|
|
||||||
|
# Build tree config. So some folks can use the built package (e.g., any of our
|
||||||
|
# own examples or applcations in this project.
|
||||||
|
configure_file( ${CMAKE_SOURCE_DIR}/cmake/PackageConfig.cmake.in
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
else()
|
||||||
|
# Version information. So find_package( XXX version ) will work.
|
||||||
|
configure_file( ${SDK_SOURCE_DIR}/cmake/PackageConfigVersion.cmake.in
|
||||||
|
"${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" @ONLY )
|
||||||
|
|
||||||
|
# Build tree config. So some folks can use the built package (e.g., any of our
|
||||||
|
# own examples or applcations in this project.
|
||||||
|
configure_file( ${SDK_SOURCE_DIR}/cmake/PackageConfig.cmake.in
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
# # Install tree config. NB we DO NOT use this. We install using brew or
|
||||||
|
# pkg-config.
|
||||||
|
# set( EXPORT_LIB_INC_DIR ${LIB_INC_DIR} )
|
||||||
|
# set( EXPORT_LIB_INC_DIR "\${PROJECT_CMAKE_DIR}/${REL_INCLUDE_DIR}" )
|
||||||
|
# configure_file( ${CMAKE_CURRENT_SOURCE_DIR}/${PROJECT_NAME}Config.cmake.in
|
||||||
|
# ${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}Config.cmake @ONLY )
|
||||||
|
#export( PACKAGE ${PROJECT_NAME} )
|
||||||
|
endif()
|
||||||
|
|
||||||
|
|
||||||
|
# write and install a cmake "find package" for cmake projects to use.
|
||||||
|
# NB: this .cmake file CANNOT refer to any source directory, only to
|
||||||
|
# _installed_ files.
|
||||||
|
configure_file( ${modules_dir}/FindPackage.cmake.in Find${PACKAGE_PKG_NAME}.cmake @ONLY )
|
||||||
|
|
||||||
|
endfunction()
|
||||||
|
|
|
@ -0,0 +1,94 @@
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
# An auxiliary function to show messages:
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
MACRO(SHOW_CONFIG_LINE MSG_TEXT VALUE_BOOL)
|
||||||
|
IF(${VALUE_BOOL})
|
||||||
|
SET(VAL_TEXT "Yes")
|
||||||
|
ELSE(${VALUE_BOOL})
|
||||||
|
SET(VAL_TEXT " No")
|
||||||
|
ENDIF(${VALUE_BOOL})
|
||||||
|
MESSAGE(STATUS " ${MSG_TEXT} : ${VAL_TEXT} ${ARGV2}")
|
||||||
|
ENDMACRO(SHOW_CONFIG_LINE)
|
||||||
|
|
||||||
|
MACRO(SHOW_CONFIG_LINE_SYSTEM MSG_TEXT VALUE_BOOL)
|
||||||
|
IF(${VALUE_BOOL})
|
||||||
|
IF(${VALUE_BOOL}_SYSTEM)
|
||||||
|
SET(VAL_TEXT "Yes (System)")
|
||||||
|
ELSE(${VALUE_BOOL}_SYSTEM)
|
||||||
|
SET(VAL_TEXT "Yes (Built-in)")
|
||||||
|
ENDIF(${VALUE_BOOL}_SYSTEM)
|
||||||
|
ELSE(${VALUE_BOOL})
|
||||||
|
SET(VAL_TEXT " No")
|
||||||
|
ENDIF(${VALUE_BOOL})
|
||||||
|
MESSAGE(STATUS " ${MSG_TEXT} : ${VAL_TEXT} ${ARGV2}")
|
||||||
|
ENDMACRO(SHOW_CONFIG_LINE_SYSTEM)
|
||||||
|
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
# Summary:
|
||||||
|
# ----------------------------------------------------------------------------
|
||||||
|
MESSAGE(STATUS "")
|
||||||
|
IF(CMAKE_COMPILER_IS_GNUCXX)
|
||||||
|
SET(MRPT_GCC_VERSION_STR "(GCC version: ${CMAKE_MRPT_GCC_VERSION})")
|
||||||
|
ENDIF(CMAKE_COMPILER_IS_GNUCXX)
|
||||||
|
|
||||||
|
MESSAGE(STATUS "+===========================================================================+")
|
||||||
|
MESSAGE(STATUS "| Resulting configuration for ${CMAKE_MRPT_COMPLETE_NAME} |")
|
||||||
|
MESSAGE(STATUS "+===========================================================================+")
|
||||||
|
MESSAGE(STATUS " _________________________ PLATFORM _____________________________")
|
||||||
|
MESSAGE(STATUS " Host : " ${CMAKE_HOST_SYSTEM_NAME} ${CMAKE_HOST_SYSTEM_VERSION} ${CMAKE_HOST_SYSTEM_PROCESSOR})
|
||||||
|
if(CMAKE_CROSSCOMPILING)
|
||||||
|
MESSAGE(STATUS " Target : " ${CMAKE_SYSTEM_NAME} ${CMAKE_SYSTEM_VERSION} ${CMAKE_SYSTEM_PROCESSOR})
|
||||||
|
endif(CMAKE_CROSSCOMPILING)
|
||||||
|
SHOW_CONFIG_LINE("Is the system big endian? " CMAKE_MRPT_IS_BIG_ENDIAN)
|
||||||
|
MESSAGE(STATUS " Word size (32/64 bit) : ${CMAKE_MRPT_WORD_SIZE}")
|
||||||
|
MESSAGE(STATUS " CMake version : " ${CMAKE_VERSION})
|
||||||
|
MESSAGE(STATUS " CMake generator : " ${CMAKE_GENERATOR})
|
||||||
|
MESSAGE(STATUS " CMake build tool : " ${CMAKE_BUILD_TOOL})
|
||||||
|
MESSAGE(STATUS " Compiler : " ${CMAKE_CXX_COMPILER_ID})
|
||||||
|
if(MSVC)
|
||||||
|
MESSAGE(STATUS " MSVC : " ${MSVC_VERSION})
|
||||||
|
endif(MSVC)
|
||||||
|
if(CMAKE_GENERATOR MATCHES Xcode)
|
||||||
|
MESSAGE(STATUS " Xcode : " ${XCODE_VERSION})
|
||||||
|
endif(CMAKE_GENERATOR MATCHES Xcode)
|
||||||
|
if(NOT CMAKE_GENERATOR MATCHES "Xcode|Visual Studio")
|
||||||
|
MESSAGE(STATUS " Configuration : " ${CMAKE_BUILD_TYPE})
|
||||||
|
endif(NOT CMAKE_GENERATOR MATCHES "Xcode|Visual Studio")
|
||||||
|
|
||||||
|
IF("${CMAKE_BUILD_TYPE}" STREQUAL "Release")
|
||||||
|
MESSAGE( STATUS "C++ flags (Release): ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_RELEASE}")
|
||||||
|
ELSEIF("${CMAKE_BUILD_TYPE}" STREQUAL "Debug")
|
||||||
|
MESSAGE( STATUS "C++ flags (Debug): ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_DEBUG}")
|
||||||
|
ENDIF()
|
||||||
|
|
||||||
|
|
||||||
|
MESSAGE(STATUS "")
|
||||||
|
MESSAGE(STATUS " __________________________ OPTIONS _____________________________")
|
||||||
|
SHOW_CONFIG_LINE("Build YDLidar-SDK as a shared library? " BUILD_SHARED_LIBS)
|
||||||
|
SHOW_CONFIG_LINE("Build Examples? " BUILD_EXAMPLES)
|
||||||
|
SHOW_CONFIG_LINE("Build C Sharp API? " BUILD_CSHARP)
|
||||||
|
SHOW_CONFIG_LINE("Build TEST? " BUILD_TEST)
|
||||||
|
MESSAGE(STATUS "")
|
||||||
|
|
||||||
|
MESSAGE(STATUS " _________________________ INSTALL _____________________")
|
||||||
|
MESSAGE(STATUS " Install prefix : ${CMAKE_INSTALL_PREFIX}")
|
||||||
|
MESSAGE(STATUS "")
|
||||||
|
|
||||||
|
IF($ENV{VERBOSE})
|
||||||
|
MESSAGE(STATUS " _________________________ COMPILER OPTIONS _____________________")
|
||||||
|
message(STATUS "Compiler: ${CMAKE_CXX_COMPILER} ${MRPT_GCC_VERSION_STR} ")
|
||||||
|
message(STATUS " C++ flags (Release): ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_RELEASE}")
|
||||||
|
message(STATUS " C++ flags (Debug): ${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_DEBUG}")
|
||||||
|
message(STATUS " Executable link flags (Release): ${CMAKE_EXE_LINKER_FLAGS} ${CMAKE_EXE_LINKER_FLAGS_RELEASE}")
|
||||||
|
message(STATUS " Executable link flags (Debug): ${CMAKE_EXE_LINKER_FLAGS} ${CMAKE_EXE_LINKER_FLAGS_DEBUG}")
|
||||||
|
message(STATUS " Lib link flags (Release): ${CMAKE_SHARED_LINKER_FLAGS} ${CMAKE_SHARED_LINKER_FLAGS_RELEASE}")
|
||||||
|
message(STATUS " Lib link flags (Debug): ${CMAKE_SHARED_LINKER_FLAGS} ${CMAKE_SHARED_LINKER_FLAGS_DEBUG}")
|
||||||
|
MESSAGE(STATUS "")
|
||||||
|
ENDIF($ENV{VERBOSE})
|
||||||
|
|
||||||
|
MESSAGE(STATUS " _______________________ WRAPPERS/BINDINGS ______________________")
|
||||||
|
SHOW_CONFIG_LINE("Python bindings (pyydlidar) " SWIG_FOUND)
|
||||||
|
SHOW_CONFIG_LINE(" - dep: Swig found? " SWIG_FOUND "[Version: ${SWIG_VERSION}]")
|
||||||
|
SHOW_CONFIG_LINE(" - dep: PythonLibs found? " PYTHONLIBS_FOUND "[Version: ${PYTHON_VERSION_STRING}]")
|
||||||
|
|
||||||
|
MESSAGE(STATUS "")
|
|
@ -0,0 +1,8 @@
|
||||||
|
cmake_minimum_required(VERSION 2.8)
|
||||||
|
include_directories(.)
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
foreach(subdir ${SUBDIRS})
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/${subdir} )
|
||||||
|
add_subdirectory(${subdir})
|
||||||
|
endforeach()
|
|
@ -0,0 +1,11 @@
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR} )
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_source_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
||||||
|
IF (WIN32)
|
||||||
|
add_to_ydlidar_libraries(Winmm)
|
||||||
|
ELSE()
|
||||||
|
add_to_ydlidar_libraries(pthread)
|
||||||
|
ENDIF()
|
|
@ -0,0 +1,148 @@
|
||||||
|
#ifndef DATATYPE_H_
|
||||||
|
#define DATATYPE_H_
|
||||||
|
|
||||||
|
#include <stddef.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <string>
|
||||||
|
#include <signal.h>
|
||||||
|
#include <cerrno>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <csignal>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#if defined(_MSC_VER)
|
||||||
|
#include <io.h>
|
||||||
|
#endif
|
||||||
|
#include "typedef.h"
|
||||||
|
|
||||||
|
#if !defined(_MSC_VER)
|
||||||
|
#include <unistd.h>
|
||||||
|
#define _itoa(value, str, radix) {sprintf(str, "%d", value);}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define UNUSED(x) (void)x
|
||||||
|
|
||||||
|
#if !defined(_MSC_VER)
|
||||||
|
# define _access access
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define valName(val) (#val)
|
||||||
|
#define valLastName(val) \
|
||||||
|
{ \
|
||||||
|
char* strToken; \
|
||||||
|
char str[64]; \
|
||||||
|
strncpy(str, (const char*)val, sizeof(str)); \
|
||||||
|
strToken = strtok(str, "."); \
|
||||||
|
while (strToken != NULL) { \
|
||||||
|
strcpy(val, (const char*)strToken); \
|
||||||
|
strToken = strtok(NULL, "."); \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @class dataFrame
|
||||||
|
* @brief data frame Structure.
|
||||||
|
*
|
||||||
|
* @author jzhang
|
||||||
|
*/
|
||||||
|
#define FRAME_PREAMBLE 0xFFEE
|
||||||
|
#define LIDAR_2D 0x2
|
||||||
|
#define DATA_FRAME 0x1
|
||||||
|
#define DEFAULT_INTENSITY 10
|
||||||
|
#define DSL(c, i) ((c << i) & (0xFF << i))
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* Type Definition Macros */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
#ifndef __WORDSIZE
|
||||||
|
/* Assume 32 */
|
||||||
|
#define __WORDSIZE 32
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(__linux__) || defined(_DARWIN)
|
||||||
|
#include <stdint.h>
|
||||||
|
typedef int SOCKET;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
struct iovec {
|
||||||
|
void *iov_base;
|
||||||
|
size_t iov_len;
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef int socklen_t;
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
#ifndef UINT8_MAX
|
||||||
|
#define UINT8_MAX (UCHAR_MAX)
|
||||||
|
#endif
|
||||||
|
#ifndef UINT16_MAX
|
||||||
|
#define UINT16_MAX (USHRT_MAX)
|
||||||
|
#endif
|
||||||
|
#ifndef UINT32_MAX
|
||||||
|
#define UINT32_MAX (ULONG_MAX)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if __WORDSIZE == 64
|
||||||
|
#define SIZE_MAX (18446744073709551615UL)
|
||||||
|
#else
|
||||||
|
#ifndef SIZE_MAX
|
||||||
|
#define SIZE_MAX (4294967295U)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#define ssize_t size_t
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define __small_endian
|
||||||
|
|
||||||
|
#ifndef __GNUC__
|
||||||
|
#define __attribute__(x)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef _AVR_
|
||||||
|
typedef uint8_t _size_t;
|
||||||
|
#define THREAD_PROC
|
||||||
|
#elif defined (WIN64)
|
||||||
|
typedef uint64_t _size_t;
|
||||||
|
#define THREAD_PROC __stdcall
|
||||||
|
#elif defined (WIN32)
|
||||||
|
typedef uint32_t _size_t;
|
||||||
|
#define THREAD_PROC __stdcall
|
||||||
|
#elif defined (_M_X64)
|
||||||
|
typedef uint64_t _size_t;
|
||||||
|
#define THREAD_PROC __stdcall
|
||||||
|
#elif defined (__GNUC__)
|
||||||
|
typedef unsigned long _size_t;
|
||||||
|
#define THREAD_PROC
|
||||||
|
#elif defined (__ICCARM__)
|
||||||
|
typedef uint32_t _size_t;
|
||||||
|
#define THREAD_PROC
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef int32_t result_t;
|
||||||
|
|
||||||
|
#define RESULT_OK 0
|
||||||
|
#define RESULT_TIMEOUT -1
|
||||||
|
#define RESULT_FAIL -2
|
||||||
|
|
||||||
|
#define INVALID_TIMESTAMP (0)
|
||||||
|
|
||||||
|
|
||||||
|
#define IS_OK(x) ( (x) == RESULT_OK )
|
||||||
|
#define IS_TIMEOUT(x) ( (x) == RESULT_TIMEOUT )
|
||||||
|
#define IS_FAIL(x) ( (x) == RESULT_FAIL )
|
||||||
|
|
||||||
|
#endif // DATATYPE_H_
|
|
@ -0,0 +1,360 @@
|
||||||
|
#pragma once
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include <conio.h>
|
||||||
|
#include <windows.h>
|
||||||
|
#include <process.h>
|
||||||
|
#include <tlhelp32.h>
|
||||||
|
#include <sys/utime.h>
|
||||||
|
#include <io.h>
|
||||||
|
#include <direct.h>
|
||||||
|
#else
|
||||||
|
#include <assert.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace base {
|
||||||
|
|
||||||
|
class Locker {
|
||||||
|
public:
|
||||||
|
enum LOCK_STATUS {
|
||||||
|
LOCK_OK = 0,
|
||||||
|
LOCK_TIMEOUT = -1,
|
||||||
|
LOCK_FAILED = -2
|
||||||
|
};
|
||||||
|
|
||||||
|
Locker() {
|
||||||
|
#ifdef _WIN32
|
||||||
|
_lock = NULL;
|
||||||
|
#endif
|
||||||
|
init();
|
||||||
|
}
|
||||||
|
|
||||||
|
~Locker() {
|
||||||
|
release();
|
||||||
|
}
|
||||||
|
|
||||||
|
Locker::LOCK_STATUS lock(unsigned long timeout = 0xFFFFFFFF) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
|
||||||
|
switch (WaitForSingleObject(_lock,
|
||||||
|
timeout == 0xFFFFFFF ? INFINITE : (DWORD)timeout)) {
|
||||||
|
case WAIT_ABANDONED:
|
||||||
|
return LOCK_FAILED;
|
||||||
|
|
||||||
|
case WAIT_OBJECT_0:
|
||||||
|
return LOCK_OK;
|
||||||
|
|
||||||
|
case WAIT_TIMEOUT:
|
||||||
|
return LOCK_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
#ifdef _MACOS
|
||||||
|
|
||||||
|
if (timeout != 0) {
|
||||||
|
if (pthread_mutex_lock(&_lock) == 0) {
|
||||||
|
return LOCK_OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (timeout == 0xFFFFFFFF) {
|
||||||
|
if (pthread_mutex_lock(&_lock) == 0) {
|
||||||
|
return LOCK_OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
else if (timeout == 0) {
|
||||||
|
if (pthread_mutex_trylock(&_lock) == 0) {
|
||||||
|
return LOCK_OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef _MACOS
|
||||||
|
else {
|
||||||
|
timespec wait_time;
|
||||||
|
timeval now;
|
||||||
|
gettimeofday(&now, NULL);
|
||||||
|
|
||||||
|
wait_time.tv_sec = timeout / 1000 + now.tv_sec;
|
||||||
|
wait_time.tv_nsec = (timeout % 1000) * 1000000 + now.tv_usec * 1000;
|
||||||
|
|
||||||
|
if (wait_time.tv_nsec >= 1000000000) {
|
||||||
|
++wait_time.tv_sec;
|
||||||
|
wait_time.tv_nsec -= 1000000000;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if !defined(__ANDROID__)
|
||||||
|
|
||||||
|
switch (pthread_mutex_timedlock(&_lock, &wait_time)) {
|
||||||
|
case 0:
|
||||||
|
return LOCK_OK;
|
||||||
|
|
||||||
|
case ETIMEDOUT:
|
||||||
|
return LOCK_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
struct timeval timenow;
|
||||||
|
struct timespec sleepytime;
|
||||||
|
/* This is just to avoid a completely busy wait */
|
||||||
|
sleepytime.tv_sec = 0;
|
||||||
|
sleepytime.tv_nsec = 10000000; /* 10ms */
|
||||||
|
|
||||||
|
while (pthread_mutex_trylock(&_lock) == EBUSY) {
|
||||||
|
gettimeofday(&timenow, NULL);
|
||||||
|
|
||||||
|
if (timenow.tv_sec >= wait_time.tv_sec &&
|
||||||
|
(timenow.tv_usec * 1000) >= wait_time.tv_nsec) {
|
||||||
|
return LOCK_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
nanosleep(&sleepytime, NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
return LOCK_OK;
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return LOCK_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void unlock() {
|
||||||
|
#ifdef _WIN32
|
||||||
|
ReleaseMutex(_lock);
|
||||||
|
#else
|
||||||
|
pthread_mutex_unlock(&_lock);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
HANDLE getLockHandle() {
|
||||||
|
return _lock;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
pthread_mutex_t *getLockHandle() {
|
||||||
|
return &_lock;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void init() {
|
||||||
|
#ifdef _WIN32
|
||||||
|
_lock = CreateMutex(NULL, FALSE, NULL);
|
||||||
|
#else
|
||||||
|
pthread_mutex_init(&_lock, NULL);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void release() {
|
||||||
|
unlock();
|
||||||
|
#ifdef _WIN32
|
||||||
|
|
||||||
|
if (_lock) {
|
||||||
|
CloseHandle(_lock);
|
||||||
|
}
|
||||||
|
|
||||||
|
_lock = NULL;
|
||||||
|
#else
|
||||||
|
pthread_mutex_destroy(&_lock);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
HANDLE _lock;
|
||||||
|
#else
|
||||||
|
pthread_mutex_t _lock;
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
class Event {
|
||||||
|
public:
|
||||||
|
|
||||||
|
enum {
|
||||||
|
EVENT_OK = 1,
|
||||||
|
EVENT_TIMEOUT = 2,
|
||||||
|
EVENT_FAILED = 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
explicit Event(bool isAutoReset = true, bool isSignal = false)
|
||||||
|
#ifdef _WIN32
|
||||||
|
: _event(NULL)
|
||||||
|
#else
|
||||||
|
: _is_signalled(isSignal)
|
||||||
|
, _isAutoReset(isAutoReset)
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
#ifdef _WIN32
|
||||||
|
_event = CreateEvent(NULL, isAutoReset ? FALSE : TRUE, isSignal ? TRUE : FALSE,
|
||||||
|
NULL);
|
||||||
|
#else
|
||||||
|
int ret = pthread_condattr_init(&_cond_cattr);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
fprintf(stderr, "Failed to init condattr...\n");
|
||||||
|
fflush(stderr);
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = pthread_condattr_setclock(&_cond_cattr, CLOCK_MONOTONIC);
|
||||||
|
pthread_mutex_init(&_cond_locker, NULL);
|
||||||
|
ret = pthread_cond_init(&_cond_var, &_cond_cattr);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
~ Event() {
|
||||||
|
release();
|
||||||
|
}
|
||||||
|
|
||||||
|
void set(bool isSignal = true) {
|
||||||
|
if (isSignal) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
SetEvent(_event);
|
||||||
|
#else
|
||||||
|
pthread_mutex_lock(&_cond_locker);
|
||||||
|
|
||||||
|
if (_is_signalled == false) {
|
||||||
|
_is_signalled = true;
|
||||||
|
pthread_cond_signal(&_cond_var);
|
||||||
|
}
|
||||||
|
|
||||||
|
pthread_mutex_unlock(&_cond_locker);
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
#ifdef _WIN32
|
||||||
|
ResetEvent(_event);
|
||||||
|
#else
|
||||||
|
pthread_mutex_lock(&_cond_locker);
|
||||||
|
_is_signalled = false;
|
||||||
|
pthread_mutex_unlock(&_cond_locker);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long wait(unsigned long timeout = 0xFFFFFFFF) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
|
||||||
|
switch (WaitForSingleObject(_event,
|
||||||
|
timeout == 0xFFFFFFF ? INFINITE : (DWORD)timeout)) {
|
||||||
|
case WAIT_FAILED:
|
||||||
|
return EVENT_FAILED;
|
||||||
|
|
||||||
|
case WAIT_OBJECT_0:
|
||||||
|
return EVENT_OK;
|
||||||
|
|
||||||
|
case WAIT_TIMEOUT:
|
||||||
|
return EVENT_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
|
return EVENT_OK;
|
||||||
|
#else
|
||||||
|
unsigned long ans = EVENT_OK;
|
||||||
|
pthread_mutex_lock(&_cond_locker);
|
||||||
|
|
||||||
|
if (!_is_signalled) {
|
||||||
|
if (timeout == 0xFFFFFFFF) {
|
||||||
|
pthread_cond_wait(&_cond_var, &_cond_locker);
|
||||||
|
} else {
|
||||||
|
struct timespec wait_time;
|
||||||
|
clock_gettime(CLOCK_MONOTONIC, &wait_time);
|
||||||
|
|
||||||
|
|
||||||
|
wait_time.tv_sec += timeout / 1000;
|
||||||
|
wait_time.tv_nsec += (timeout % 1000) * 1000000ULL;
|
||||||
|
|
||||||
|
if (wait_time.tv_nsec >= 1000000000) {
|
||||||
|
++wait_time.tv_sec;
|
||||||
|
wait_time.tv_nsec -= 1000000000;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (pthread_cond_timedwait(&_cond_var, &_cond_locker, &wait_time)) {
|
||||||
|
case 0:
|
||||||
|
// signalled
|
||||||
|
break;
|
||||||
|
|
||||||
|
case ETIMEDOUT:
|
||||||
|
// time up
|
||||||
|
ans = EVENT_TIMEOUT;
|
||||||
|
goto _final;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
ans = EVENT_FAILED;
|
||||||
|
goto _final;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
assert(_is_signalled);
|
||||||
|
|
||||||
|
if (_isAutoReset) {
|
||||||
|
_is_signalled = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
_final:
|
||||||
|
pthread_mutex_unlock(&_cond_locker);
|
||||||
|
|
||||||
|
return ans;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
protected:
|
||||||
|
|
||||||
|
void release() {
|
||||||
|
#ifdef _WIN32
|
||||||
|
CloseHandle(_event);
|
||||||
|
#else
|
||||||
|
pthread_condattr_destroy(&_cond_cattr);
|
||||||
|
pthread_mutex_destroy(&_cond_locker);
|
||||||
|
pthread_cond_destroy(&_cond_var);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
HANDLE _event;
|
||||||
|
#else
|
||||||
|
pthread_condattr_t _cond_cattr;
|
||||||
|
pthread_cond_t _cond_var;
|
||||||
|
pthread_mutex_t _cond_locker;
|
||||||
|
bool _is_signalled;
|
||||||
|
bool _isAutoReset;
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
class ScopedLocker {
|
||||||
|
public :
|
||||||
|
explicit ScopedLocker(Locker &l): _binded(l) {
|
||||||
|
_binded.lock();
|
||||||
|
}
|
||||||
|
|
||||||
|
void forceUnlock() {
|
||||||
|
_binded.unlock();
|
||||||
|
}
|
||||||
|
~ScopedLocker() {
|
||||||
|
_binded.unlock();
|
||||||
|
}
|
||||||
|
Locker &_binded;
|
||||||
|
};
|
||||||
|
|
||||||
|
}//base
|
||||||
|
}//core
|
||||||
|
}//ydlidar
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,143 @@
|
||||||
|
#pragma once
|
||||||
|
#include "v8stdint.h"
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include <conio.h>
|
||||||
|
#include <windows.h>
|
||||||
|
#include <io.h>
|
||||||
|
#include <process.h>
|
||||||
|
#else
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(__ANDROID__)
|
||||||
|
#define pthread_cancel(x) 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define CLASS_THREAD(c , x ) Thread::ThreadCreateObjectFunctor<c, &c::x>(this)
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace base {
|
||||||
|
|
||||||
|
class Thread {
|
||||||
|
public:
|
||||||
|
|
||||||
|
template <class CLASS, int (CLASS::*PROC)(void)> static Thread
|
||||||
|
ThreadCreateObjectFunctor(CLASS *pthis) {
|
||||||
|
return createThread(createThreadAux<CLASS, PROC>, pthis);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class CLASS, int (CLASS::*PROC)(void) > static _size_t THREAD_PROC
|
||||||
|
createThreadAux(void *param) {
|
||||||
|
return (static_cast<CLASS *>(param)->*PROC)();
|
||||||
|
}
|
||||||
|
|
||||||
|
static Thread createThread(thread_proc_t proc, void *param = NULL) {
|
||||||
|
Thread thread_(proc, param);
|
||||||
|
#if defined(_WIN32)
|
||||||
|
thread_._handle = (_size_t)(_beginthreadex(NULL, 0,
|
||||||
|
(unsigned int (__stdcall *)(void *))proc, param, 0, NULL));
|
||||||
|
#else
|
||||||
|
assert(sizeof(thread_._handle) >= sizeof(pthread_t));
|
||||||
|
|
||||||
|
pthread_create((pthread_t *)&thread_._handle, NULL, (void *(*)(void *))proc,
|
||||||
|
param);
|
||||||
|
#endif
|
||||||
|
return thread_;
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit Thread(): _param(NULL), _func(NULL), _handle(0) {}
|
||||||
|
virtual ~Thread() {}
|
||||||
|
_size_t getHandle() {
|
||||||
|
return _handle;
|
||||||
|
}
|
||||||
|
int terminate() {
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
if (!this->_handle) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (TerminateThread(reinterpret_cast<HANDLE>(this->_handle), -1)) {
|
||||||
|
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
|
||||||
|
this->_handle = NULL;
|
||||||
|
return 0;
|
||||||
|
} else {
|
||||||
|
return -2;
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (!this->_handle) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
return pthread_cancel((pthread_t)this->_handle);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
void *getParam() {
|
||||||
|
return _param;
|
||||||
|
}
|
||||||
|
int join(unsigned long timeout = -1) {
|
||||||
|
if (!this->_handle) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
switch (WaitForSingleObject(reinterpret_cast<HANDLE>(this->_handle), timeout)) {
|
||||||
|
case WAIT_OBJECT_0:
|
||||||
|
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
|
||||||
|
this->_handle = NULL;
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
case WAIT_ABANDONED:
|
||||||
|
return -2;
|
||||||
|
|
||||||
|
case WAIT_TIMEOUT:
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
UNUSED(timeout);
|
||||||
|
void *res;
|
||||||
|
int s = -1;
|
||||||
|
s = pthread_cancel((pthread_t)(this->_handle));
|
||||||
|
|
||||||
|
if (s != 0) {
|
||||||
|
}
|
||||||
|
|
||||||
|
s = pthread_join((pthread_t)(this->_handle), &res);
|
||||||
|
|
||||||
|
if (s != 0) {
|
||||||
|
}
|
||||||
|
|
||||||
|
if (res == PTHREAD_CANCELED) {
|
||||||
|
printf("%lu thread has been canceled\n", this->_handle);
|
||||||
|
this->_handle = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool operator== (const Thread &right) {
|
||||||
|
return this->_handle == right._handle;
|
||||||
|
}
|
||||||
|
protected:
|
||||||
|
explicit Thread(thread_proc_t proc, void *param): _param(param), _func(proc),
|
||||||
|
_handle(0) {}
|
||||||
|
void *_param;
|
||||||
|
thread_proc_t _func;
|
||||||
|
_size_t _handle;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
}//base
|
||||||
|
}//core
|
||||||
|
}//ydlidar
|
||||||
|
|
|
@ -0,0 +1,57 @@
|
||||||
|
#include "timer.h"
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include <mmsystem.h>
|
||||||
|
#pragma comment(lib, "Winmm.lib")
|
||||||
|
|
||||||
|
namespace impl {
|
||||||
|
|
||||||
|
static LARGE_INTEGER _current_freq;
|
||||||
|
|
||||||
|
void HPtimer_reset() {
|
||||||
|
BOOL ans = QueryPerformanceFrequency(&_current_freq);
|
||||||
|
_current_freq.QuadPart /= 1000;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t getHDTimer() {
|
||||||
|
LARGE_INTEGER current;
|
||||||
|
QueryPerformanceCounter(¤t);
|
||||||
|
|
||||||
|
return (uint32_t)(current.QuadPart / (_current_freq.QuadPart));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint64_t getCurrentTime() {
|
||||||
|
FILETIME t;
|
||||||
|
GetSystemTimeAsFileTime(&t);
|
||||||
|
return ((((uint64_t)t.dwHighDateTime) << 32) | ((uint64_t)t.dwLowDateTime)) *
|
||||||
|
100;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
BEGIN_STATIC_CODE(timer_cailb) {
|
||||||
|
HPtimer_reset();
|
||||||
|
} END_STATIC_CODE(timer_cailb)
|
||||||
|
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
|
||||||
|
namespace impl {
|
||||||
|
uint32_t getHDTimer() {
|
||||||
|
struct timespec t;
|
||||||
|
t.tv_sec = t.tv_nsec = 0;
|
||||||
|
clock_gettime(CLOCK_MONOTONIC, &t);
|
||||||
|
return t.tv_sec * 1000L + t.tv_nsec / 1000000L;
|
||||||
|
}
|
||||||
|
uint64_t getCurrentTime() {
|
||||||
|
#if HAS_CLOCK_GETTIME
|
||||||
|
struct timespec tim;
|
||||||
|
clock_gettime(CLOCK_REALTIME, &tim);
|
||||||
|
return static_cast<uint64_t>(tim.tv_sec) * 1000000000LL + tim.tv_nsec;
|
||||||
|
#else
|
||||||
|
struct timeval timeofday;
|
||||||
|
gettimeofday(&timeofday, NULL);
|
||||||
|
return static_cast<uint64_t>(timeofday.tv_sec) * 1000000000LL +
|
||||||
|
static_cast<uint64_t>(timeofday.tv_usec) * 1000LL;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -0,0 +1,51 @@
|
||||||
|
#pragma once
|
||||||
|
#include "v8stdint.h"
|
||||||
|
#include <assert.h>
|
||||||
|
#include <time.h>
|
||||||
|
#include <inttypes.h>
|
||||||
|
|
||||||
|
|
||||||
|
#define BEGIN_STATIC_CODE( _blockname_ ) \
|
||||||
|
static class _static_code_##_blockname_ { \
|
||||||
|
public: \
|
||||||
|
_static_code_##_blockname_ ()
|
||||||
|
|
||||||
|
|
||||||
|
#define END_STATIC_CODE( _blockname_ ) \
|
||||||
|
} _instance_##_blockname_;
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include <windows.h>
|
||||||
|
#define delay(x) ::Sleep(x)
|
||||||
|
#else
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
static inline void delay(uint32_t ms) {
|
||||||
|
while (ms >= 1000) {
|
||||||
|
usleep(1000 * 1000);
|
||||||
|
ms -= 1000;
|
||||||
|
};
|
||||||
|
|
||||||
|
if (ms != 0) {
|
||||||
|
usleep(ms * 1000);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
namespace impl {
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
void HPtimer_reset();
|
||||||
|
#endif
|
||||||
|
uint32_t getHDTimer();
|
||||||
|
uint64_t getCurrentTime();
|
||||||
|
} // namespace impl
|
||||||
|
|
||||||
|
|
||||||
|
#define getms() impl::getHDTimer()
|
||||||
|
#define getTime() impl::getCurrentTime()
|
|
@ -0,0 +1,17 @@
|
||||||
|
#ifndef TYPEDEF_H_
|
||||||
|
#define TYPEDEF_H_
|
||||||
|
#include <stdlib.h>
|
||||||
|
#if defined(_WIN32) && !defined(__MINGW32__)
|
||||||
|
typedef signed char int8_t;
|
||||||
|
typedef unsigned char uint8_t;
|
||||||
|
typedef short int16_t;
|
||||||
|
typedef unsigned short uint16_t;
|
||||||
|
typedef int int32_t;
|
||||||
|
typedef unsigned int uint32_t;
|
||||||
|
typedef __int64 int64_t;
|
||||||
|
typedef unsigned __int64 uint64_t;
|
||||||
|
#else
|
||||||
|
#include <stdint.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // TYPEDEF_H_
|
|
@ -0,0 +1,18 @@
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef WIN32
|
||||||
|
#ifdef ydlidar_IMPORTS
|
||||||
|
#define YDLIDAR_API __declspec(dllimport)
|
||||||
|
#else
|
||||||
|
#ifdef ydlidarStatic_IMPORTS
|
||||||
|
#define YDLIDAR_API
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define YDLIDAR_API __declspec(dllexport)
|
||||||
|
#endif // YDLIDAR_STATIC_EXPORTS
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#else
|
||||||
|
#define YDLIDAR_API
|
||||||
|
#endif // ifdef WIN32
|
|
@ -0,0 +1,144 @@
|
||||||
|
#ifndef V8STDINT_H_
|
||||||
|
#define V8STDINT_H_
|
||||||
|
#include "datatype.h"
|
||||||
|
typedef _size_t (THREAD_PROC *thread_proc_t)(void *);
|
||||||
|
|
||||||
|
//Socket
|
||||||
|
|
||||||
|
#ifndef TRUE
|
||||||
|
#define TRUE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef FALSE
|
||||||
|
#define FALSE 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef htonll
|
||||||
|
#ifdef _BIG_ENDIAN
|
||||||
|
#define htonll(x) (x)
|
||||||
|
#define ntohll(x) (x)
|
||||||
|
#else
|
||||||
|
#define htonll(x) ((((uint64)htonl(x)) << 32) + htonl(x >> 32))
|
||||||
|
#define ntohll(x) ((((uint64)ntohl(x)) << 32) + ntohl(x >> 32))
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* Socket Macros */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#define SHUT_RD 0
|
||||||
|
#define SHUT_WR 1
|
||||||
|
#define SHUT_RDWR 2
|
||||||
|
#define ACCEPT(a,b,c) accept(a,b,c)
|
||||||
|
#define CONNECT(a,b,c) connect(a,b,c)
|
||||||
|
#define CLOSE(a) closesocket(a)
|
||||||
|
#define READ(a,b,c) read(a,b,c)
|
||||||
|
#define RECV(a,b,c,d) recv(a, (char *)b, c, d)
|
||||||
|
#define RECVFROM(a,b,c,d,e,f) recvfrom(a, (char *)b, c, d, (sockaddr *)e, (int *)f)
|
||||||
|
#define RECV_FLAGS MSG_WAITALL
|
||||||
|
#define SELECT(a,b,c,d,e) select((int32_t)a,b,c,d,e)
|
||||||
|
#define SEND(a,b,c,d) send(a, (const char *)b, (int)c, d)
|
||||||
|
#define SENDTO(a,b,c,d,e,f) sendto(a, (const char *)b, (int)c, d, e, f)
|
||||||
|
#define SEND_FLAGS 0
|
||||||
|
#define SENDFILE(a,b,c,d) sendfile(a, b, c, d)
|
||||||
|
#define SET_SOCKET_ERROR(x,y) errno=y
|
||||||
|
#define SOCKET_ERROR_INTERUPT EINTR
|
||||||
|
#define SOCKET_ERROR_TIMEDOUT EAGAIN
|
||||||
|
#define WRITE(a,b,c) write(a,b,c)
|
||||||
|
#define WRITEV(a,b,c) Writev(b, c)
|
||||||
|
#define GETSOCKOPT(a,b,c,d,e) getsockopt(a,b,c,(char *)d, (int *)e)
|
||||||
|
#define SETSOCKOPT(a,b,c,d,e) setsockopt(a,b,c,(char *)d, (int)e)
|
||||||
|
#define GETHOSTBYNAME(a) gethostbyname(a)
|
||||||
|
#define IOCTLSOCKET(a, b, c) ioctlsocket(a,b,(u_long*)c)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(__linux__) || defined(_DARWIN)
|
||||||
|
#define ACCEPT(a,b,c) accept(a,b,c)
|
||||||
|
#define CONNECT(a,b,c) connect(a,b,c)
|
||||||
|
#define CLOSE(a) close(a)
|
||||||
|
#define READ(a,b,c) read(a,b,c)
|
||||||
|
#define RECV(a,b,c,d) recv(a, (void *)b, c, d)
|
||||||
|
#define RECVFROM(a,b,c,d,e,f) recvfrom(a, (char *)b, c, d, (sockaddr *)e, f)
|
||||||
|
#define RECV_FLAGS MSG_WAITALL
|
||||||
|
#define SELECT(a,b,c,d,e) select(a,b,c,d,e)
|
||||||
|
#define SEND(a,b,c,d) send(a, (const int8_t *)b, c, d)
|
||||||
|
#define SENDTO(a,b,c,d,e,f) sendto(a, (const int8_t *)b, c, d, e, f)
|
||||||
|
#define SEND_FLAGS 0
|
||||||
|
#define SENDFILE(a,b,c,d) sendfile(a, b, c, d)
|
||||||
|
#define SET_SOCKET_ERROR(x,y) errno=y
|
||||||
|
#define SOCKET_ERROR_INTERUPT EINTR
|
||||||
|
#define SOCKET_ERROR_TIMEDOUT EAGAIN
|
||||||
|
#define WRITE(a,b,c) write(a,b,c)
|
||||||
|
#define WRITEV(a,b,c) writev(a, b, c)
|
||||||
|
#define GETSOCKOPT(a,b,c,d,e) getsockopt((int)a,(int)b,(int)c,(void *)d,(socklen_t *)e)
|
||||||
|
#define SETSOCKOPT(a,b,c,d,e) setsockopt((int)a,(int)b,(int)c,(const void *)d,(int)e)
|
||||||
|
#define GETHOSTBYNAME(a) gethostbyname(a)
|
||||||
|
#define IOCTLSOCKET(a, b, c) ioctl(a,b,c)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* File Macros */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
#define STRUCT_STAT struct stat
|
||||||
|
#define LSTAT(x,y) lstat(x,y)
|
||||||
|
#define FILE_HANDLE FILE *
|
||||||
|
#define CLEARERR(x) clearerr(x)
|
||||||
|
#define FCLOSE(x) fclose(x)
|
||||||
|
#define FEOF(x) feof(x)
|
||||||
|
#define FERROR(x) ferror(x)
|
||||||
|
#define FFLUSH(x) fflush(x)
|
||||||
|
#define FILENO(s) fileno(s)
|
||||||
|
#define FOPEN(x,y) fopen(x, y)
|
||||||
|
//#define FREAD(a,b,c,d) fread(a, b, c, d)
|
||||||
|
#define FSTAT(s, st) fstat(FILENO(s), st)
|
||||||
|
//#define FWRITE(a,b,c,d) fwrite(a, b, c, d)
|
||||||
|
#define STAT_BLK_SIZE(x) ((x).st_blksize)
|
||||||
|
|
||||||
|
#define DEFAULT_CONNECTION_TIMEOUT_SEC 2
|
||||||
|
#define DEFAULT_CONNECTION_TIMEOUT_USEC 800000
|
||||||
|
|
||||||
|
#define DEFAULT_REV_TIMEOUT_SEC 2
|
||||||
|
#define DEFAULT_REV_TIMEOUT_USEC 800000
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* Misc Macros */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#define STRTOULL(x) _atoi64(x)
|
||||||
|
#else
|
||||||
|
#define STRTOULL(x) strtoull(x, NULL, 10)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#define SNPRINTF _snprintf
|
||||||
|
#define PRINTF printf
|
||||||
|
#define VPRINTF vprintf
|
||||||
|
#define FPRINTF fprintf
|
||||||
|
#else
|
||||||
|
#define SNPRINTF snprintf
|
||||||
|
#define PRINTF printf
|
||||||
|
#define VPRINTF vprintf
|
||||||
|
#define FPRINTF fprintf
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define MILLISECONDS_CONVERSION 1000
|
||||||
|
#define MICROSECONDS_CONVERSION 1000000
|
||||||
|
#define NANOECONDS_CONVERSION 1000000000
|
||||||
|
|
||||||
|
#include "ydlidar.h"
|
||||||
|
|
||||||
|
#endif // V8STDINT_H_
|
|
@ -0,0 +1,194 @@
|
||||||
|
#ifndef YDLIDAR_H_
|
||||||
|
#define YDLIDAR_H_
|
||||||
|
#include "datatype.h"
|
||||||
|
#include <signal.h>
|
||||||
|
|
||||||
|
/// PropertyBuilderByName Used to generate class member variables
|
||||||
|
/// and generate set and get methods
|
||||||
|
/// type Variable type
|
||||||
|
/// access_permission Variable access(public, priavte, protected)
|
||||||
|
#define PropertyBuilderByName(type, name, access_permission)\
|
||||||
|
access_permission:\
|
||||||
|
type m_##name;\
|
||||||
|
public:\
|
||||||
|
inline void set##name(type v) {\
|
||||||
|
m_##name = v;\
|
||||||
|
}\
|
||||||
|
inline type get##name() const {\
|
||||||
|
return m_##name;\
|
||||||
|
}\
|
||||||
|
|
||||||
|
|
||||||
|
// Determine if sigaction is available
|
||||||
|
#if __APPLE__ || _POSIX_C_SOURCE >= 1 || _XOPEN_SOURCE || _POSIX_SOURCE
|
||||||
|
#define HAS_SIGACTION
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static volatile sig_atomic_t g_signal_status = 0;
|
||||||
|
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
static struct sigaction old_action;
|
||||||
|
#else
|
||||||
|
typedef void (* signal_handler_t)(int);
|
||||||
|
static signal_handler_t old_signal_handler = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
inline struct sigaction
|
||||||
|
set_sigaction(int signal_value, const struct sigaction &action)
|
||||||
|
#else
|
||||||
|
inline signal_handler_t
|
||||||
|
set_signal_handler(int signal_value, signal_handler_t signal_handler)
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
struct sigaction old_action;
|
||||||
|
ssize_t ret = sigaction(signal_value, &action, &old_action);
|
||||||
|
|
||||||
|
if (ret == -1)
|
||||||
|
#else
|
||||||
|
signal_handler_t old_signal_handler = std::signal(signal_value, signal_handler);
|
||||||
|
|
||||||
|
// NOLINTNEXTLINE(readability/braces)
|
||||||
|
if (old_signal_handler == SIG_ERR)
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
const size_t error_length = 1024;
|
||||||
|
// NOLINTNEXTLINE(runtime/arrays)
|
||||||
|
char error_string[error_length];
|
||||||
|
#ifndef _WIN32
|
||||||
|
#if (defined(_GNU_SOURCE) && !defined(ANDROID) &&(_POSIX_C_SOURCE >= 200112L))
|
||||||
|
char *msg = strerror_r(errno, error_string, error_length);
|
||||||
|
|
||||||
|
if (msg != error_string) {
|
||||||
|
strncpy(error_string, msg, error_length);
|
||||||
|
msg[error_length - 1] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
int error_status = strerror_r(errno, error_string, error_length);
|
||||||
|
|
||||||
|
if (error_status != 0) {
|
||||||
|
throw std::runtime_error("Failed to get error string for errno: " +
|
||||||
|
std::to_string(errno));
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
strerror_s(error_string, error_length, errno);
|
||||||
|
#endif
|
||||||
|
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
|
||||||
|
throw std::runtime_error(
|
||||||
|
std::string("Failed to set SIGINT signal handler: (" + std::to_string(errno) + ")") +
|
||||||
|
error_string);
|
||||||
|
// *INDENT-ON*
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
return old_action;
|
||||||
|
#else
|
||||||
|
return old_signal_handler;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void trigger_interrupt_guard_condition(int signal_value) {
|
||||||
|
g_signal_status = signal_value;
|
||||||
|
signal(signal_value, SIG_DFL);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
signal_handler(int signal_value, siginfo_t *siginfo, void *context)
|
||||||
|
#else
|
||||||
|
signal_handler(int signal_value)
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
// TODO(wjwwood): remove? move to console logging at some point?
|
||||||
|
printf("signal_handler(%d)\n", signal_value);
|
||||||
|
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
|
||||||
|
if (old_action.sa_flags & SA_SIGINFO) {
|
||||||
|
if (old_action.sa_sigaction != NULL) {
|
||||||
|
old_action.sa_sigaction(signal_value, siginfo, context);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (
|
||||||
|
old_action.sa_handler != NULL && // Is set
|
||||||
|
old_action.sa_handler != SIG_DFL && // Is not default
|
||||||
|
old_action.sa_handler != SIG_IGN) { // Is not ignored
|
||||||
|
old_action.sa_handler(signal_value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (old_signal_handler) {
|
||||||
|
old_signal_handler(signal_value);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
trigger_interrupt_guard_condition(signal_value);
|
||||||
|
}
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace base {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief initialize system state
|
||||||
|
* @param argc
|
||||||
|
* @param argv
|
||||||
|
*/
|
||||||
|
inline void init() {
|
||||||
|
#ifdef HAS_SIGACTION
|
||||||
|
struct sigaction action;
|
||||||
|
memset(&action, 0, sizeof(action));
|
||||||
|
sigemptyset(&action.sa_mask);
|
||||||
|
action.sa_sigaction = ::signal_handler;
|
||||||
|
action.sa_flags = SA_SIGINFO;
|
||||||
|
::old_action = set_sigaction(SIGINT, action);
|
||||||
|
set_sigaction(SIGTERM, action);
|
||||||
|
|
||||||
|
#else
|
||||||
|
::old_signal_handler = set_signal_handler(SIGINT, ::signal_handler);
|
||||||
|
// Register an on_shutdown hook to restore the old signal handler.
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* @brief ok
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
inline bool ok() {
|
||||||
|
return g_signal_status == 0;
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* @brief shutdown
|
||||||
|
*/
|
||||||
|
inline void shutdown() {
|
||||||
|
trigger_interrupt_guard_condition(SIGINT);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief fileExists
|
||||||
|
* @param filename
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
inline bool fileExists(const std::string &filename) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
struct _stat info = {0};
|
||||||
|
int ret = _stat(filename.c_str(), &info);
|
||||||
|
#else
|
||||||
|
struct stat info = {0};
|
||||||
|
int ret = stat(filename.c_str(), &info);
|
||||||
|
#endif
|
||||||
|
return (ret == 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
}//base
|
||||||
|
}//core
|
||||||
|
}// namespace ydlidar
|
||||||
|
|
||||||
|
|
||||||
|
#endif // YDLIDAR_H_
|
|
@ -0,0 +1,5 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_source_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
|
@ -0,0 +1,134 @@
|
||||||
|
#pragma once
|
||||||
|
#include <core/base/v8stdint.h>
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace common {
|
||||||
|
class ChannelDevice {
|
||||||
|
public:
|
||||||
|
ChannelDevice() {}
|
||||||
|
virtual ~ChannelDevice() {}
|
||||||
|
/**
|
||||||
|
* @brief bind device port
|
||||||
|
* @return true if successfully bind, otherwise false
|
||||||
|
*/
|
||||||
|
virtual bool bindport(const char *, uint32_t) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* @brief open device
|
||||||
|
* @return true if successfully open, otherwise false
|
||||||
|
*/
|
||||||
|
virtual bool open() = 0;
|
||||||
|
/**
|
||||||
|
* @brief Whether is open
|
||||||
|
* @return true if already open, otherwise false
|
||||||
|
*/
|
||||||
|
virtual bool isOpen() = 0;
|
||||||
|
/**
|
||||||
|
* @brief close serial port or network
|
||||||
|
*/
|
||||||
|
virtual void closePort() = 0;
|
||||||
|
/**
|
||||||
|
* @brief Return the number of characters in the buffer.
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
virtual size_t available() = 0;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* @brief Flush the input and output buffers
|
||||||
|
*/
|
||||||
|
virtual void flush() = 0;
|
||||||
|
/**
|
||||||
|
* @brief Block until there is serial or network data to read or read_timeout_constant
|
||||||
|
* number of milliseconds have elapsed. The return value is greater than zero when
|
||||||
|
* the function exits with the serial port or network buffer is greater than or
|
||||||
|
* equal to data_count, false otherwise(due to timeout or select interruption).
|
||||||
|
* @param data_count A size_t that indicates how many bytes should be wait from
|
||||||
|
* the given serial port or network buffer.
|
||||||
|
* @param timeout waiting timeout time
|
||||||
|
* @param returned_size if it is not NULL, the actual number of bytes will be returned.
|
||||||
|
* @return A size_t representing the number of bytes wait as a result of the
|
||||||
|
* call to wait.
|
||||||
|
*/
|
||||||
|
virtual int waitfordata(size_t data_count, uint32_t timeout = -1,
|
||||||
|
size_t *returned_size = NULL) = 0;
|
||||||
|
/*! Read a given amount of bytes from the serial port or network and return a string
|
||||||
|
* containing the data.
|
||||||
|
*
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A std::string containing the data read from the port.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
virtual std::string readSize(size_t size = 1) = 0;
|
||||||
|
|
||||||
|
/*! Write a string to the serial port or network.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \param size A size_t that indicates how many bytes should be written from
|
||||||
|
* the given data buffer.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*/
|
||||||
|
virtual size_t writeData(const uint8_t *data, size_t size) = 0;
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port or network into a given buffer.
|
||||||
|
*
|
||||||
|
* The read function will return in one of three cases:
|
||||||
|
* * The number of requested bytes was read.
|
||||||
|
* * In this case the number of bytes requested will match the size_t
|
||||||
|
* returned by read.
|
||||||
|
* * A timeout occurred, in this case the number of bytes read will not
|
||||||
|
* match the amount requested, but no exception will be thrown. One of
|
||||||
|
* two possible timeouts occurred:
|
||||||
|
* * The inter byte timeout expired, this means that number of
|
||||||
|
* milliseconds elapsed between receiving bytes from the serial port
|
||||||
|
* exceeded the inter byte timeout.
|
||||||
|
* * The total timeout expired, which is calculated by multiplying the
|
||||||
|
* read timeout multiplier by the number of requested bytes and then
|
||||||
|
* added to the read timeout constant. If that total number of
|
||||||
|
* milliseconds elapses after the initial call to read a timeout will
|
||||||
|
* occur.
|
||||||
|
* * An exception occurred, in this case an actual exception will be thrown.
|
||||||
|
*
|
||||||
|
* \param buffer An uint8_t array of at least the requested size.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
virtual size_t readData(uint8_t *data, size_t size) = 0;
|
||||||
|
/*!
|
||||||
|
* @brief Set the DTR handshaking line to the given level.
|
||||||
|
* @param level Defaults to true.
|
||||||
|
*/
|
||||||
|
|
||||||
|
virtual bool setDTR(bool level = true) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
/*!
|
||||||
|
* @brief Returns the singal byte time.
|
||||||
|
* @return one byte transfer time
|
||||||
|
*/
|
||||||
|
virtual int getByteTime() {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns a human-readable description of the given error code
|
||||||
|
* or the last error code of a socket or serial port
|
||||||
|
* @return error information
|
||||||
|
*/
|
||||||
|
virtual const char *DescribeError() {
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
}//common
|
||||||
|
}//core
|
||||||
|
}//ydlidar
|
|
@ -0,0 +1,532 @@
|
||||||
|
#pragma once
|
||||||
|
#include <core/base/v8stdint.h>
|
||||||
|
#include <core/base/thread.h>
|
||||||
|
#include <core/base/locker.h>
|
||||||
|
#include <map>
|
||||||
|
#include "ydlidar_protocol.h"
|
||||||
|
#include "ydlidar_def.h"
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
using namespace base;
|
||||||
|
namespace common {
|
||||||
|
|
||||||
|
class DriverInterface {
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* @brief Set and Get LiDAR single channel.
|
||||||
|
* Whether LiDAR communication channel is a single-channel
|
||||||
|
* @note For a single-channel LiDAR, if the settings are reversed.\n
|
||||||
|
* an error will occur in obtaining device information and the LiDAR will Faied to Start.\n
|
||||||
|
* For dual-channel LiDAR, if th setttings are reversed.\n
|
||||||
|
* the device information cannot be obtained.\n
|
||||||
|
* Set the single channel to match the LiDAR.
|
||||||
|
* @remarks
|
||||||
|
<table>
|
||||||
|
<tr><th>G1/G2/G2A/G2C <td>false
|
||||||
|
<tr><th>G4/G5/G4B/G4PRO/G6/G7/F4/F4PRO <td>false
|
||||||
|
<tr><th>S4/S4B/X4/R2/G4C <td>false
|
||||||
|
<tr><th>S2/X2/X2L <td>true
|
||||||
|
<tr><th>TG15/TG30/TG50 <td>false
|
||||||
|
<tr><th>TX8/TX20 <td>true
|
||||||
|
<tr><th>T5/T15 <td>false
|
||||||
|
<tr><th> <td>true
|
||||||
|
</table>
|
||||||
|
* @see DriverInterface::setSingleChannel and DriverInterface::getSingleChannel
|
||||||
|
*/
|
||||||
|
PropertyBuilderByName(bool, SingleChannel, protected);
|
||||||
|
/**
|
||||||
|
* @brief Set and Get LiDAR Type.
|
||||||
|
* @note Refer to the table below for the LiDAR Type.\n
|
||||||
|
* Set the LiDAR Type to match the LiDAR.
|
||||||
|
* @remarks
|
||||||
|
<table>
|
||||||
|
<tr><th>G1/G2A/G2/G2C <td>[TYPE_TRIANGLE](\ref LidarTypeID::TYPE_TRIANGLE)
|
||||||
|
<tr><th>G4/G5/G4B/G4C/G4PRO <td>[TYPE_TRIANGLE](\ref LidarTypeID::TYPE_TRIANGLE)
|
||||||
|
<tr><th>G6/G7/F4/F4PRO <td>[TYPE_TRIANGLE](\ref LidarTypeID::TYPE_TRIANGLE)
|
||||||
|
<tr><th>S4/S4B/X4/R2/S2/X2/X2L <td>[TYPE_TRIANGLE](\ref LidarTypeID::TYPE_TRIANGLE)
|
||||||
|
<tr><th>TG15/TG30/TG50/TX8/TX20 <td>[TYPE_TOF](\ref LidarTypeID::TYPE_TOF)
|
||||||
|
<tr><th>T5/T15 <td>[TYPE_TOF_NET](\ref LidarTypeID::TYPE_TOF_NET)
|
||||||
|
</table>
|
||||||
|
* @see [LidarTypeID](\ref LidarTypeID)
|
||||||
|
* @see DriverInterface::setLidarType and DriverInterface::getLidarType
|
||||||
|
*/
|
||||||
|
PropertyBuilderByName(int, LidarType, protected);
|
||||||
|
/**
|
||||||
|
* @brief Set and Get Sampling interval.
|
||||||
|
* @note Negative correlation between sampling interval and lidar sampling rate.\n
|
||||||
|
* sampling interval = 1e9 / sampling rate(/s)\n
|
||||||
|
* Set the LiDAR sampling interval to match the LiDAR.
|
||||||
|
* @see DriverInterface::setPointTime and DriverInterface::getPointTime
|
||||||
|
*/
|
||||||
|
PropertyBuilderByName(uint32_t, PointTime, protected);
|
||||||
|
/**
|
||||||
|
* @brief Set and Get LiDAR Support Motor DTR.
|
||||||
|
* @note The current paramter settings are only valid
|
||||||
|
* if the LiDAR is connected to the serial port adapter via USB.\n
|
||||||
|
* If the LiDAR does not have external motor enable line,
|
||||||
|
* the current paramters do not need to be set.\n
|
||||||
|
* Set the LiDAR Motro DTR to match the LiDAR.
|
||||||
|
* @remarks
|
||||||
|
<table>
|
||||||
|
<tr><th>S4/S4B/S2/X2/X2L/X4 <td>true
|
||||||
|
<tr><th>TX8/TX20 <td>true
|
||||||
|
<tr><th>G4/G5/G4C/G4PRO/F4/F4PRO/G6/G7 <td>false
|
||||||
|
<tr><th>G1/G2A/G2C/R2/G2/G4B <td>false
|
||||||
|
<tr><th>TG15/TG30/TG50 <td>false
|
||||||
|
<tr><th>T5/T15 <td>false
|
||||||
|
</table>
|
||||||
|
* @see DriverInterface::setSupportMotorDtrCtrl and DriverInterface::getSupportMotorDtrCtrl
|
||||||
|
*/
|
||||||
|
PropertyBuilderByName(bool, SupportMotorDtrCtrl, protected);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set and Get LiDAR HeartBeat function.
|
||||||
|
* @note The current paramter settings are only valid
|
||||||
|
* if the LiDAR is BigScreen.\n
|
||||||
|
* Set the LiDAR HeartBeat to match the LiDAR.
|
||||||
|
* @remarks
|
||||||
|
<table>
|
||||||
|
<tr><th>G4/G4PRO <td>false
|
||||||
|
</table>
|
||||||
|
* @see DriverInterface::setHeartBeat and DriverInterface::getHeartBeat
|
||||||
|
*/
|
||||||
|
PropertyBuilderByName(bool, HeartBeat, protected);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @par Constructor
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
DriverInterface() : serial_port(""),
|
||||||
|
m_baudrate(8000),
|
||||||
|
m_intensities(false),
|
||||||
|
scan_node_buf(NULL),
|
||||||
|
scan_node_count(0),
|
||||||
|
package_Sample_Index(0),
|
||||||
|
retryCount(0),
|
||||||
|
isAutoReconnect(true),
|
||||||
|
isAutoconnting(false) {
|
||||||
|
m_SingleChannel = false;
|
||||||
|
m_LidarType = TYPE_TRIANGLE;
|
||||||
|
m_PointTime = 0;
|
||||||
|
m_SupportMotorDtrCtrl = true;
|
||||||
|
m_HeartBeat = false;
|
||||||
|
m_isScanning = false;
|
||||||
|
m_isConnected = false;
|
||||||
|
m_config.motor_rpm = 1200;
|
||||||
|
m_config.laserScanFrequency = 50;
|
||||||
|
m_config.correction_angle = 20640;
|
||||||
|
m_config.correction_distance = 6144;
|
||||||
|
m_driverErrno = NoError;
|
||||||
|
m_InvalidNodeCount = 0;
|
||||||
|
m_BufferSize = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~DriverInterface() {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Connecting Lidar \n
|
||||||
|
* After the connection if successful, you must use ::disconnect to close
|
||||||
|
* @param[in] port_path serial port
|
||||||
|
* @param[in] baudrate serial baudrate,YDLIDAR-SS:
|
||||||
|
* 230400 G2-SS-1 R2-SS-1
|
||||||
|
* @return connection status
|
||||||
|
* @retval 0 success
|
||||||
|
* @retval < 0 failed
|
||||||
|
* @note After the connection if successful, you must use ::disconnect to close
|
||||||
|
* @see function ::YDlidarDriver::disconnect ()
|
||||||
|
*/
|
||||||
|
virtual result_t connect(const char *port_path, uint32_t baudrate = 8000) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns a human-readable description of the given error code
|
||||||
|
* or the last error code of a socket or serial port
|
||||||
|
* @param isTCP TCP or UDP
|
||||||
|
* @return error information
|
||||||
|
*/
|
||||||
|
virtual const char *DescribeError(bool isTCP = true) = 0;
|
||||||
|
|
||||||
|
static const char *DescribeDriverError(DriverError err) {
|
||||||
|
char const *errorString = "Unknown error";
|
||||||
|
|
||||||
|
switch (err) {
|
||||||
|
case NoError:
|
||||||
|
errorString = ("No error");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case DeviceNotFoundError:
|
||||||
|
errorString = ("Device is not found");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case PermissionError:
|
||||||
|
errorString = ("Device is not permission");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case UnsupportedOperationError:
|
||||||
|
errorString = ("unsupported operation");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case NotOpenError:
|
||||||
|
errorString = ("Device is not open");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TimeoutError:
|
||||||
|
errorString = ("Operation timed out");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BlockError:
|
||||||
|
errorString = ("Device Block");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case NotBufferError:
|
||||||
|
errorString = ("Device Failed");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TrembleError:
|
||||||
|
errorString = ("Device Tremble");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LaserFailureError:
|
||||||
|
errorString = ("Laser Failure");
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// an empty string will be interpreted as "Unknown error"
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return errorString;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* @brief Disconnect the LiDAR.
|
||||||
|
*/
|
||||||
|
virtual void disconnect() = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get SDK Version \n
|
||||||
|
* static function
|
||||||
|
* @return Version
|
||||||
|
*/
|
||||||
|
virtual std::string getSDKVersion() = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Is the Lidar in the scan \n
|
||||||
|
* @return scanning status
|
||||||
|
* @retval true scanning
|
||||||
|
* @retval false non-scanning
|
||||||
|
*/
|
||||||
|
virtual bool isscanning() const = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Is it connected to the lidar \n
|
||||||
|
* @return connection status
|
||||||
|
* @retval true connected
|
||||||
|
* @retval false Non-connected
|
||||||
|
*/
|
||||||
|
virtual bool isconnected() const = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Is there intensity \n
|
||||||
|
* @param[in] isintensities intentsity
|
||||||
|
* true intensity
|
||||||
|
* false no intensity
|
||||||
|
*/
|
||||||
|
virtual void setIntensities(const bool &isintensities) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief whether to support hot plug \n
|
||||||
|
* @param[in] enable hot plug :
|
||||||
|
* true support
|
||||||
|
* false no support
|
||||||
|
*/
|
||||||
|
virtual void setAutoReconnect(const bool &enable) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get current scan update configuration.
|
||||||
|
* @returns scanCfg structure.
|
||||||
|
*/
|
||||||
|
virtual lidarConfig getFinishedScanCfg() const {
|
||||||
|
return m_config;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief get Health status \n
|
||||||
|
* @return result status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE or RESULT_TIMEOUT failed
|
||||||
|
*/
|
||||||
|
virtual result_t getHealth(device_health &health,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief get Device information \n
|
||||||
|
* @param[in] info Device information
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return result status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE or RESULT_TIMEOUT failed
|
||||||
|
*/
|
||||||
|
virtual result_t getDeviceInfo(device_info &info,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Turn on scanning \n
|
||||||
|
* @param[in] force Scan mode
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return result status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Just turn it on once
|
||||||
|
*/
|
||||||
|
virtual result_t startScan(bool force = false,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief turn off scanning \n
|
||||||
|
* @return result status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
*/
|
||||||
|
virtual result_t stop() = 0;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get a circle of laser data \n
|
||||||
|
* @param[in] nodebuffer Laser data
|
||||||
|
* @param[in] count one circle of laser points
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Before starting, you must start the start the scan successfully with the ::startScan function
|
||||||
|
*/
|
||||||
|
virtual result_t grabScanData(node_info *nodebuffer, size_t &count,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0 ;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get lidar scan frequency \n
|
||||||
|
* @param[in] frequency scanning frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t getScanFrequency(scan_frequency &frequency,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Increase the scanning frequency by 1.0 HZ \n
|
||||||
|
* @param[in] frequency scanning frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t setScanFrequencyAdd(scan_frequency &frequency,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reduce the scanning frequency by 1.0 HZ \n
|
||||||
|
* @param[in] frequency scanning frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t setScanFrequencyDis(scan_frequency &frequency,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Increase the scanning frequency by 0.1 HZ \n
|
||||||
|
* @param[in] frequency scanning frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t setScanFrequencyAddMic(scan_frequency &frequency,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reduce the scanning frequency by 0.1 HZ \n
|
||||||
|
* @param[in] frequency scanning frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t setScanFrequencyDisMic(scan_frequency &frequency,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get lidar sampling frequency \n
|
||||||
|
* @param[in] frequency sampling frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t getSamplingRate(sampling_rate &rate,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set the lidar sampling frequency \n
|
||||||
|
* @param[in] rate sampling frequency
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t setSamplingRate(sampling_rate &rate,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief get lidar zero offset angle \n
|
||||||
|
* @param[in] angle zero offset angle
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
virtual result_t getZeroOffsetAngle(offset_angle &angle,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief set lidar heart beat \n
|
||||||
|
* @param[in] beat heart beat status
|
||||||
|
* @param[in] timeout timeout
|
||||||
|
* @return return status
|
||||||
|
* @retval RESULT_OK success
|
||||||
|
* @retval RESULT_FAILE failed
|
||||||
|
* @note Non-scan state, perform currect operation.
|
||||||
|
*/
|
||||||
|
|
||||||
|
virtual result_t setScanHeartbeat(scan_heart_beat &beat,
|
||||||
|
uint32_t timeout = DEFAULT_TIMEOUT) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief setDriverError
|
||||||
|
* @param er
|
||||||
|
*/
|
||||||
|
virtual void setDriverError(const DriverError &er) {
|
||||||
|
ScopedLocker l(_error_lock);
|
||||||
|
m_driverErrno = er;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief getDriverError
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
virtual DriverError getDriverError() {
|
||||||
|
ScopedLocker l(_error_lock);
|
||||||
|
return m_driverErrno;
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
enum {
|
||||||
|
YDLIDAR_F4 = 1,/**< F4 LiDAR Model. */
|
||||||
|
YDLIDAR_T1 = 2,/**< T1 LiDAR Model. */
|
||||||
|
YDLIDAR_F2 = 3,/**< F2 LiDAR Model. */
|
||||||
|
YDLIDAR_S4 = 4,/**< S4 LiDAR Model. */
|
||||||
|
YDLIDAR_G4 = 5,/**< G4 LiDAR Model. */
|
||||||
|
YDLIDAR_X4 = 6,/**< X4 LiDAR Model. */
|
||||||
|
YDLIDAR_G4PRO = 7,/**< G4PRO LiDAR Model. */
|
||||||
|
YDLIDAR_F4PRO = 8,/**< F4PRO LiDAR Model. */
|
||||||
|
YDLIDAR_R2 = 9,/**< R2 LiDAR Model. */
|
||||||
|
YDLIDAR_G10 = 10,/**< G10 LiDAR Model. */
|
||||||
|
YDLIDAR_S4B = 11,/**< S4B LiDAR Model. */
|
||||||
|
YDLIDAR_S2 = 12,/**< S2 LiDAR Model. */
|
||||||
|
YDLIDAR_G6 = 13,/**< G6 LiDAR Model. */
|
||||||
|
YDLIDAR_G2A = 14,/**< G2A LiDAR Model. */
|
||||||
|
YDLIDAR_G2B = 15,/**< G2 LiDAR Model. */
|
||||||
|
YDLIDAR_G2C = 16,/**< G2C LiDAR Model. */
|
||||||
|
YDLIDAR_G4B = 17,/**< G4B LiDAR Model. */
|
||||||
|
YDLIDAR_G4C = 18,/**< G4C LiDAR Model. */
|
||||||
|
YDLIDAR_G1 = 19,/**< G1 LiDAR Model. */
|
||||||
|
YDLIDAR_G5 = 20,/**< G5 LiDAR Model. */
|
||||||
|
YDLIDAR_G7 = 21,/**< G7 LiDAR Model. */
|
||||||
|
|
||||||
|
YDLIDAR_TG15 = 100,/**< TG15 LiDAR Model. */
|
||||||
|
YDLIDAR_TG30 = 101,/**< T30 LiDAR Model. */
|
||||||
|
YDLIDAR_TG50 = 102,/**< TG50 LiDAR Model. */
|
||||||
|
|
||||||
|
YDLIDAR_T15 = 200,/**< T15 LiDAR Model. */
|
||||||
|
YDLIDAR_Tail,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum {
|
||||||
|
YDLIDAR_RATE_4K = 0,/**< 4K sample rate code */
|
||||||
|
YDLIDAR_RATE_8K = 1,/**< 8K sample rate code */
|
||||||
|
YDLIDAR_RATE_9K = 2,/**< 9K sample rate code */
|
||||||
|
YDLIDAR_RATE_10K = 3,/**< 10K sample rate code */
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
enum {
|
||||||
|
DEFAULT_TIMEOUT = 2000, /**< Default timeout. */
|
||||||
|
DEFAULT_HEART_BEAT = 1000, /**< Default heartbeat timeout. */
|
||||||
|
MAX_SCAN_NODES = 7200, /**< Default Max Scan Count. */
|
||||||
|
DEFAULT_TIMEOUT_COUNT = 1, /**< Default Timeout Count. */
|
||||||
|
};
|
||||||
|
|
||||||
|
protected:
|
||||||
|
/* Variable for LIDAR compatibility */
|
||||||
|
/// LiDAR Scanning state
|
||||||
|
bool m_isScanning;
|
||||||
|
/// LiDAR connected state
|
||||||
|
bool m_isConnected;
|
||||||
|
/// Scan Data Event
|
||||||
|
Event _dataEvent;
|
||||||
|
/// Data Locker
|
||||||
|
Locker _lock;
|
||||||
|
/// Parse Data thread
|
||||||
|
Thread _thread;
|
||||||
|
/// command locker
|
||||||
|
Locker _cmd_lock;
|
||||||
|
/// driver error locker
|
||||||
|
Locker _error_lock;
|
||||||
|
|
||||||
|
|
||||||
|
/// LiDAR com port or IP Address
|
||||||
|
std::string serial_port;
|
||||||
|
/// baudrate or IP port
|
||||||
|
uint32_t m_baudrate;
|
||||||
|
/// LiDAR intensity
|
||||||
|
bool m_intensities;
|
||||||
|
|
||||||
|
/// LiDAR Point pointer
|
||||||
|
node_info *scan_node_buf;
|
||||||
|
/// LiDAR scan count
|
||||||
|
size_t scan_node_count; //<! LiDAR Scan Count
|
||||||
|
/// package sample index
|
||||||
|
uint16_t package_Sample_Index;
|
||||||
|
///
|
||||||
|
int retryCount;
|
||||||
|
/// auto reconnect
|
||||||
|
bool isAutoReconnect;
|
||||||
|
/// auto connecting state
|
||||||
|
bool isAutoconnting;
|
||||||
|
lidarConfig m_config;
|
||||||
|
|
||||||
|
/// number of last error
|
||||||
|
DriverError m_driverErrno;
|
||||||
|
|
||||||
|
///invalid node count
|
||||||
|
int m_InvalidNodeCount;
|
||||||
|
size_t m_BufferSize;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
}//common
|
||||||
|
}//core
|
||||||
|
}//ydlidar
|
|
@ -0,0 +1,113 @@
|
||||||
|
/*********************************************************************
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2018, EAIBOT, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of the Willow Garage nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*********************************************************************/
|
||||||
|
#pragma once
|
||||||
|
#include <core/base/datatype.h>
|
||||||
|
#include <vector>
|
||||||
|
#include "ydlidar_def.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The Laser Debug struct
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t W3F4CusMajor_W4F0CusMinor;
|
||||||
|
uint8_t W4F3Model_W3F0DebugInfTranVer;
|
||||||
|
uint8_t W3F4HardwareVer_W4F0FirewareMajor;
|
||||||
|
uint8_t W7F0FirewareMinor;
|
||||||
|
uint8_t W3F4BoradHardVer_W4F0Moth;
|
||||||
|
uint8_t W2F5Output2K4K5K_W5F0Date;
|
||||||
|
uint8_t W1F6GNoise_W1F5SNoise_W1F4MotorCtl_W4F0SnYear;
|
||||||
|
uint8_t W7F0SnNumH;
|
||||||
|
uint8_t W7F0SnNumL;
|
||||||
|
uint8_t W7F0Health;
|
||||||
|
uint8_t W3F4CusHardVer_W4F0CusSoftVer;
|
||||||
|
uint8_t W7F0LaserCurrent;
|
||||||
|
uint8_t MaxDebugIndex;
|
||||||
|
} LaserDebug;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The Laser Scan Data struct
|
||||||
|
* @par usage
|
||||||
|
* @code
|
||||||
|
* LaserScan data;
|
||||||
|
* for(int i = 0; i < data.points.size(); i++) {
|
||||||
|
* //current LiDAR angle
|
||||||
|
* float angle = data.points[i].angle;
|
||||||
|
* //current LiDAR range
|
||||||
|
* float range = data.points[i].range;
|
||||||
|
* //current LiDAR intensity
|
||||||
|
* float intensity = data.points[i].intensity;
|
||||||
|
* //current LiDAR point stamp
|
||||||
|
* uint64_t timestamp = data.stamp + i * data.config.time_increment * 1e9;
|
||||||
|
* }
|
||||||
|
* LaserScanDestroy(&data);
|
||||||
|
* @endcode
|
||||||
|
* @par convert to ROS sensor_msgs::LaserScan
|
||||||
|
* @code
|
||||||
|
* LaserScan scan;
|
||||||
|
* sensor_msgs::LaserScan scan_msg;
|
||||||
|
* std::string frame_id = "laser_frame";
|
||||||
|
* ros::Time start_scan_time;
|
||||||
|
* start_scan_time.sec = scan.stamp/1000000000ul;
|
||||||
|
* start_scan_time.nsec = scan.stamp%1000000000ul;
|
||||||
|
* scan_msg.header.stamp = start_scan_time;
|
||||||
|
* scan_msg.header.frame_id = frame_id;
|
||||||
|
* scan_msg.angle_min =(scan.config.min_angle);
|
||||||
|
* scan_msg.angle_max = (scan.config.max_angle);
|
||||||
|
* scan_msg.angle_increment = (scan.config.angle_increment);
|
||||||
|
* scan_msg.scan_time = scan.config.scan_time;
|
||||||
|
* scan_msg.time_increment = scan.config.time_increment;
|
||||||
|
* scan_msg.range_min = (scan.config.min_range);
|
||||||
|
* scan_msg.range_max = (scan.config.max_range);
|
||||||
|
* int size = (scan.config.max_angle - scan.config.min_angle)/ scan.config.angle_increment + 1;
|
||||||
|
* scan_msg.ranges.resize(size);
|
||||||
|
* scan_msg.intensities.resize(size);
|
||||||
|
* for(int i=0; i < scan.points.size(); i++) {
|
||||||
|
* int index = std::ceil((scan.points[i].angle - scan.config.min_angle)/scan.config.angle_increment);
|
||||||
|
* if(index >=0 && index < size) {
|
||||||
|
* scan_msg.ranges[index] = scan.points[i].range;
|
||||||
|
* scan_msg.intensities[index] = scan.points[i].intensity;
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* @endcode
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
/// System time when first range was measured in nanoseconds
|
||||||
|
uint64_t stamp;
|
||||||
|
/// Array of lidar points
|
||||||
|
std::vector<LaserPoint> points;
|
||||||
|
/// Configuration of scan
|
||||||
|
LaserConfig config;
|
||||||
|
} LaserScan;
|
|
@ -0,0 +1,39 @@
|
||||||
|
//
|
||||||
|
// The MIT License (MIT)
|
||||||
|
//
|
||||||
|
// Copyright (c) 2020 EAIBOT. All rights reserved.
|
||||||
|
//
|
||||||
|
// Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
// of this software and associated documentation files (the "Software"), to deal
|
||||||
|
// in the Software without restriction, including without limitation the rights
|
||||||
|
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
// copies of the Software, and to permit persons to whom the Software is
|
||||||
|
// furnished to do so, subject to the following conditions:
|
||||||
|
//
|
||||||
|
// The above copyright notice and this permission notice shall be included in
|
||||||
|
// all copies or substantial portions of the Software.
|
||||||
|
//
|
||||||
|
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
// SOFTWARE.
|
||||||
|
//
|
||||||
|
|
||||||
|
#include <core/common/ydlidar_def.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
void LaserFanInit(LaserFan *to_init) {
|
||||||
|
if (to_init) {
|
||||||
|
memset(to_init, 0, sizeof(LaserFan));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void LaserFanDestroy(LaserFan *to_destroy) {
|
||||||
|
if (to_destroy && to_destroy->points) {
|
||||||
|
free(to_destroy->points);
|
||||||
|
to_destroy->points = NULL;
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,240 @@
|
||||||
|
//
|
||||||
|
// The MIT License (MIT)
|
||||||
|
//
|
||||||
|
// Copyright (c) 2020 EAIBOT. All rights reserved.
|
||||||
|
//
|
||||||
|
// Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
// of this software and associated documentation files (the "Software"), to deal
|
||||||
|
// in the Software without restriction, including without limitation the rights
|
||||||
|
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
// copies of the Software, and to permit persons to whom the Software is
|
||||||
|
// furnished to do so, subject to the following conditions:
|
||||||
|
//
|
||||||
|
// The above copyright notice and this permission notice shall be included in
|
||||||
|
// all copies or substantial portions of the Software.
|
||||||
|
//
|
||||||
|
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
// SOFTWARE.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef YDLIDAR_DEF_H_
|
||||||
|
#define YDLIDAR_DEF_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <core/base/typedef.h>
|
||||||
|
#include <core/base/utils.h>
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** Device Type ID */
|
||||||
|
typedef enum {
|
||||||
|
YDLIDAR_TYPE_SERIAL = 0x0,/**< serial type.*/
|
||||||
|
YDLIDAR_TYPE_TCP = 0x1,/**< socket tcp type.*/
|
||||||
|
YDLIDAR_TYPC_UDP = 0x2,/**< socket udp type.*/
|
||||||
|
} DeviceTypeID;
|
||||||
|
|
||||||
|
/** Lidar Type ID */
|
||||||
|
typedef enum {
|
||||||
|
TYPE_TOF = 0,/**< TG TX LiDAR.*/
|
||||||
|
TYPE_TRIANGLE = 1,/**< G4. G6. G2 LiDAR.*/
|
||||||
|
TYPE_TOF_NET = 2,/**< T15 LiDAR.*/
|
||||||
|
TYPE_Tail,
|
||||||
|
} LidarTypeID;
|
||||||
|
|
||||||
|
|
||||||
|
/** Lidar Properties,Lidar Can set and get parameter property index.\n
|
||||||
|
* float properties must be float type, not double type.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
/* char* properties */
|
||||||
|
LidarPropSerialPort = 0,/**< Lidar serial port or network ipaddress */
|
||||||
|
LidarPropIgnoreArray,/**< Lidar ignore angle array */
|
||||||
|
/* int properties */
|
||||||
|
LidarPropSerialBaudrate = 10,/**< lidar serial baudrate or network port */
|
||||||
|
LidarPropLidarType,/**< lidar type code */
|
||||||
|
LidarPropDeviceType,/**< lidar connection type code */
|
||||||
|
LidarPropSampleRate,/**< lidar sample rate */
|
||||||
|
LidarPropAbnormalCheckCount,/**< abnormal maximum check times */
|
||||||
|
/* float properties */
|
||||||
|
LidarPropMaxRange = 20,/**< lidar maximum range */
|
||||||
|
LidarPropMinRange,/**< lidar minimum range */
|
||||||
|
LidarPropMaxAngle,/**< lidar maximum angle */
|
||||||
|
LidarPropMinAngle,/**< lidar minimum angle */
|
||||||
|
LidarPropScanFrequency,/**< lidar scanning frequency */
|
||||||
|
/* bool properties */
|
||||||
|
LidarPropFixedResolution = 30,/**< fixed angle resolution flag */
|
||||||
|
LidarPropReversion,/**< lidar reversion flag */
|
||||||
|
LidarPropInverted,/**< lidar inverted flag */
|
||||||
|
LidarPropAutoReconnect,/**< lidar hot plug flag */
|
||||||
|
LidarPropSingleChannel,/**< lidar single-channel flag */
|
||||||
|
LidarPropIntenstiy,/**< lidar intensity flag */
|
||||||
|
LidarPropSupportMotorDtrCtrl,/**< lidar support motor Dtr ctrl flag */
|
||||||
|
LidarPropSupportHeartBeat,/**< lidar support heartbeat flag */
|
||||||
|
} LidarProperty;
|
||||||
|
|
||||||
|
/// lidar instance
|
||||||
|
typedef struct {
|
||||||
|
void *lidar;///< CYdLidar instance
|
||||||
|
} YDLidar;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
NoError = 0,
|
||||||
|
DeviceNotFoundError,
|
||||||
|
PermissionError,
|
||||||
|
UnsupportedOperationError,
|
||||||
|
UnknownError,
|
||||||
|
TimeoutError,
|
||||||
|
NotOpenError,
|
||||||
|
BlockError,
|
||||||
|
NotBufferError,
|
||||||
|
TrembleError,
|
||||||
|
LaserFailureError,
|
||||||
|
} DriverError;
|
||||||
|
|
||||||
|
#pragma pack(1)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The Laser Point struct
|
||||||
|
* @note angle unit: rad.\n
|
||||||
|
* range unit: meter.\n
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
/// lidar angle. unit(rad)
|
||||||
|
float angle;
|
||||||
|
/// lidar range. unit(m)
|
||||||
|
float range;
|
||||||
|
/// lidar intensity
|
||||||
|
float intensity;
|
||||||
|
} LaserPoint;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief A struct for returning configuration from the YDLIDAR
|
||||||
|
* @note angle unit: rad.\n
|
||||||
|
* time unit: second.\n
|
||||||
|
* range unit: meter.\n
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
/// Start angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top.
|
||||||
|
float min_angle;
|
||||||
|
/// Stop angle for the laser scan [rad]. 0 is forward and angles are measured clockwise when viewing YDLIDAR from the top.
|
||||||
|
float max_angle;
|
||||||
|
/// angle resoltuion [rad]
|
||||||
|
float angle_increment;
|
||||||
|
/// Scan resoltuion [s]
|
||||||
|
float time_increment;
|
||||||
|
/// Time between scans
|
||||||
|
float scan_time;
|
||||||
|
/// Minimum range [m]
|
||||||
|
float min_range;
|
||||||
|
/// Maximum range [m]
|
||||||
|
float max_range;
|
||||||
|
} LaserConfig;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The Laser Scan Data struct
|
||||||
|
* @par usage
|
||||||
|
* @code
|
||||||
|
* LaserScan data;
|
||||||
|
* for(int i = 0; i < data.npoints; i++) {
|
||||||
|
* //current LiDAR angle
|
||||||
|
* float angle = data.points[i].angle;
|
||||||
|
* //current LiDAR range
|
||||||
|
* float range = data.points[i].range;
|
||||||
|
* //current LiDAR intensity
|
||||||
|
* float intensity = data.points[i].intensity;
|
||||||
|
* //current LiDAR point stamp
|
||||||
|
* uint64_t timestamp = data.stamp + i * data.config.time_increment * 1e9;
|
||||||
|
* }
|
||||||
|
* LaserScanDestroy(&data);
|
||||||
|
* @endcode
|
||||||
|
* @par convert to ROS sensor_msgs::LaserScan
|
||||||
|
* @code
|
||||||
|
* LaserScan scan;
|
||||||
|
* sensor_msgs::LaserScan scan_msg;
|
||||||
|
* std::string frame_id = "laser_frame";
|
||||||
|
* ros::Time start_scan_time;
|
||||||
|
* start_scan_time.sec = scan.stamp/1000000000ul;
|
||||||
|
* start_scan_time.nsec = scan.stamp%1000000000ul;
|
||||||
|
* scan_msg.header.stamp = start_scan_time;
|
||||||
|
* scan_msg.header.frame_id = frame_id;
|
||||||
|
* scan_msg.angle_min =(scan.config.min_angle);
|
||||||
|
* scan_msg.angle_max = (scan.config.max_angle);
|
||||||
|
* scan_msg.angle_increment = (scan.config.angle_increment);
|
||||||
|
* scan_msg.scan_time = scan.config.scan_time;
|
||||||
|
* scan_msg.time_increment = scan.config.time_increment;
|
||||||
|
* scan_msg.range_min = (scan.config.min_range);
|
||||||
|
* scan_msg.range_max = (scan.config.max_range);
|
||||||
|
* int size = (scan.config.max_angle - scan.config.min_angle)/ scan.config.angle_increment + 1;
|
||||||
|
* scan_msg.ranges.resize(size);
|
||||||
|
* scan_msg.intensities.resize(size);
|
||||||
|
* for(int i=0; i < scan.npoints; i++) {
|
||||||
|
* int index = std::ceil((scan.points[i].angle - scan.config.min_angle)/scan.config.angle_increment);
|
||||||
|
* if(index >=0 && index < size) {
|
||||||
|
* scan_msg.ranges[index] = scan.points[i].range;
|
||||||
|
* scan_msg.intensities[index] = scan.points[i].intensity;
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* LaserScanDestroy(&scan);
|
||||||
|
* @endcode
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
/// System time when first range was measured in nanoseconds
|
||||||
|
uint64_t stamp;///< ns
|
||||||
|
/// Array of lidar points
|
||||||
|
uint32_t npoints;
|
||||||
|
LaserPoint *points;
|
||||||
|
/// Configuration of scan
|
||||||
|
LaserConfig config;
|
||||||
|
} LaserFan;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief c string
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
/// data
|
||||||
|
char data[50];
|
||||||
|
} string_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief lidar ports
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
string_t port[8];
|
||||||
|
} LidarPort;
|
||||||
|
|
||||||
|
/** The numeric version information struct. */
|
||||||
|
typedef struct {
|
||||||
|
uint8_t hardware; /**< Hardware version*/
|
||||||
|
uint8_t soft_major; /**< major number */
|
||||||
|
uint8_t soft_minor; /**< minor number */
|
||||||
|
uint8_t soft_patch; /**< patch number */
|
||||||
|
uint8_t sn[16]; /**< serial number*/
|
||||||
|
} LidarVersion;
|
||||||
|
|
||||||
|
#pragma pack()
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief initialize LaserFan
|
||||||
|
* @param to_init
|
||||||
|
*/
|
||||||
|
YDLIDAR_API void LaserFanInit(LaserFan *to_init);
|
||||||
|
/**
|
||||||
|
* Destroy an instance of LaserFan points
|
||||||
|
*/
|
||||||
|
YDLIDAR_API void LaserFanDestroy(LaserFan *to_destroy);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#endif // YDLIDAR_DEF_H_
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,394 @@
|
||||||
|
/*********************************************************************
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2018, EAIBOT, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of the Willow Garage nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*********************************************************************/
|
||||||
|
#pragma once
|
||||||
|
#include <core/base/v8stdint.h>
|
||||||
|
#include <vector>
|
||||||
|
#include <functional>
|
||||||
|
|
||||||
|
/// Count the number of elements in a statically allocated array.
|
||||||
|
#if !defined(_countof)
|
||||||
|
#define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0]))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @name PI constant
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#ifndef M_PI
|
||||||
|
#define M_PI 3.1415926
|
||||||
|
#endif
|
||||||
|
/** @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @name sun noise flag constant
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define SUNNOISEINTENSITY 0xff
|
||||||
|
/** @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @name glass noise flag constant
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define GLASSNOISEINTENSITY 0xfe
|
||||||
|
/** @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**@name LIDAR CMD Protocol
|
||||||
|
* @brief LiDAR request and response CMD
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define LIDAR_CMD_STOP 0x65
|
||||||
|
#define LIDAR_CMD_SCAN 0x60
|
||||||
|
#define LIDAR_CMD_FORCE_SCAN 0x61
|
||||||
|
#define LIDAR_CMD_RESET 0x80
|
||||||
|
#define LIDAR_CMD_FORCE_STOP 0x00
|
||||||
|
#define LIDAR_CMD_GET_EAI 0x55
|
||||||
|
#define LIDAR_CMD_GET_DEVICE_INFO 0x90
|
||||||
|
#define LIDAR_CMD_GET_DEVICE_HEALTH 0x92
|
||||||
|
#define LIDAR_ANS_TYPE_DEVINFO 0x4
|
||||||
|
#define LIDAR_ANS_TYPE_DEVHEALTH 0x6
|
||||||
|
#define LIDAR_CMD_SYNC_BYTE 0xA5
|
||||||
|
#define LIDAR_CMDFLAG_HAS_PAYLOAD 0x80
|
||||||
|
#define LIDAR_ANS_SYNC_BYTE1 0xA5
|
||||||
|
#define LIDAR_ANS_SYNC_BYTE2 0x5A
|
||||||
|
#define LIDAR_ANS_TYPE_MEASUREMENT 0x81
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0)
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0)
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_DISTANCE_SHIFT 2
|
||||||
|
#define LIDAR_RESP_MEASUREMENT_ANGLE_SAMPLE_SHIFT 8
|
||||||
|
|
||||||
|
#define LIDAR_CMD_RUN_POSITIVE 0x06
|
||||||
|
#define LIDAR_CMD_RUN_INVERSION 0x07
|
||||||
|
#define LIDAR_CMD_SET_AIMSPEED_ADDMIC 0x09
|
||||||
|
#define LIDAR_CMD_SET_AIMSPEED_DISMIC 0x0A
|
||||||
|
#define LIDAR_CMD_SET_AIMSPEED_ADD 0x0B
|
||||||
|
#define LIDAR_CMD_SET_AIMSPEED_DIS 0x0C
|
||||||
|
#define LIDAR_CMD_GET_AIMSPEED 0x0D
|
||||||
|
|
||||||
|
#define LIDAR_CMD_SET_SAMPLING_RATE 0xD0
|
||||||
|
#define LIDAR_CMD_GET_SAMPLING_RATE 0xD1
|
||||||
|
#define LIDAR_STATUS_OK 0x0
|
||||||
|
#define LIDAR_STATUS_WARNING 0x1
|
||||||
|
#define LIDAR_STATUS_ERROR 0x2
|
||||||
|
|
||||||
|
#define LIDAR_CMD_ENABLE_LOW_POWER 0x01
|
||||||
|
#define LIDAR_CMD_DISABLE_LOW_POWER 0x02
|
||||||
|
#define LIDAR_CMD_STATE_MODEL_MOTOR 0x05
|
||||||
|
#define LIDAR_CMD_ENABLE_CONST_FREQ 0x0E
|
||||||
|
#define LIDAR_CMD_DISABLE_CONST_FREQ 0x0F
|
||||||
|
|
||||||
|
#define LIDAR_CMD_GET_OFFSET_ANGLE 0x93
|
||||||
|
#define LIDAR_CMD_SAVE_SET_EXPOSURE 0x94
|
||||||
|
#define LIDAR_CMD_SET_LOW_EXPOSURE 0x95
|
||||||
|
#define LIDAR_CMD_ADD_EXPOSURE 0x96
|
||||||
|
#define LIDAR_CMD_DIS_EXPOSURE 0x97
|
||||||
|
|
||||||
|
#define LIDAR_CMD_SET_HEART_BEAT 0xD9
|
||||||
|
|
||||||
|
/** @} LIDAR CMD Protocol */
|
||||||
|
|
||||||
|
/// Maximuum number of samples in a packet
|
||||||
|
#define PackageSampleMaxLngth 0x100
|
||||||
|
|
||||||
|
/// CT Package Type
|
||||||
|
typedef enum {
|
||||||
|
CT_Normal = 0,///< Normal package
|
||||||
|
CT_RingStart = 1,///< Starting package
|
||||||
|
CT_Tail,
|
||||||
|
} CT;
|
||||||
|
|
||||||
|
/// Default Node Quality
|
||||||
|
#define Node_Default_Quality (10)
|
||||||
|
/// Starting Node
|
||||||
|
#define Node_Sync 1
|
||||||
|
/// Normal Node
|
||||||
|
#define Node_NotSync 2
|
||||||
|
/// Package Header Size
|
||||||
|
#define PackagePaidBytes 10
|
||||||
|
/// Package Header
|
||||||
|
#define PH 0x55AA
|
||||||
|
/// Normal Package size
|
||||||
|
#define TrianglePackageDataSize 40
|
||||||
|
/// TOF Normal package size
|
||||||
|
#define TOFPackageDataSize 80
|
||||||
|
|
||||||
|
/// ET LiDAR Protocol Type
|
||||||
|
typedef enum {
|
||||||
|
Protocol_V1 = 0,///< V1 version
|
||||||
|
Protocol_V2 = 1,///< V2 version
|
||||||
|
} ProtocolVer;
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#pragma pack(1)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/// LiDAR Node info
|
||||||
|
struct node_info {
|
||||||
|
uint8_t sync_flag; ///< sync flag
|
||||||
|
uint16_t sync_quality;///< intensity
|
||||||
|
uint16_t angle_q6_checkbit; ///< angle
|
||||||
|
uint16_t distance_q2; ///< range
|
||||||
|
uint64_t stamp; ///< time stamp
|
||||||
|
uint32_t delay_time; ///< delay time
|
||||||
|
uint8_t scan_frequence;///< scan frequency. invalid: 0
|
||||||
|
uint8_t debugInfo;///< debug information
|
||||||
|
uint8_t index;///< package index
|
||||||
|
uint8_t error_package;///< error package state
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// package node info
|
||||||
|
struct PackageNode {
|
||||||
|
uint8_t PakageSampleQuality;///< intensity
|
||||||
|
uint16_t PakageSampleDistance;///< range
|
||||||
|
} __attribute__((packed));
|
||||||
|
|
||||||
|
/// TOF Intensity package node info
|
||||||
|
struct TOFPackageNode {
|
||||||
|
uint16_t PakageSampleQuality;
|
||||||
|
uint16_t PakageSampleDistance;
|
||||||
|
} __attribute__((packed));
|
||||||
|
|
||||||
|
/// LiDAR Intensity Nodes Package
|
||||||
|
struct node_package {
|
||||||
|
uint16_t package_Head;///< package header
|
||||||
|
uint8_t package_CT;///< package ct
|
||||||
|
uint8_t nowPackageNum;///< package number
|
||||||
|
uint16_t packageFirstSampleAngle;///< first sample angle
|
||||||
|
uint16_t packageLastSampleAngle;///< last sample angle
|
||||||
|
uint16_t checkSum;///< checksum
|
||||||
|
PackageNode packageSample[PackageSampleMaxLngth];
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// TOF LiDAR Intensity Nodes Package
|
||||||
|
struct tof_node_package {
|
||||||
|
uint16_t package_Head;
|
||||||
|
uint8_t package_CT;
|
||||||
|
uint8_t nowPackageNum;
|
||||||
|
uint16_t packageFirstSampleAngle;
|
||||||
|
uint16_t packageLastSampleAngle;
|
||||||
|
uint16_t checkSum;
|
||||||
|
TOFPackageNode packageSample[PackageSampleMaxLngth];
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Normal Nodes package
|
||||||
|
struct node_packages {
|
||||||
|
uint16_t package_Head;///< package header
|
||||||
|
uint8_t package_CT;///< package ct
|
||||||
|
uint8_t nowPackageNum; ///< package number
|
||||||
|
uint16_t packageFirstSampleAngle;///< first sample angle
|
||||||
|
uint16_t packageLastSampleAngle;///< last sample angle
|
||||||
|
uint16_t checkSum;///< checksum
|
||||||
|
uint16_t packageSampleDistance[PackageSampleMaxLngth];
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Device Information
|
||||||
|
struct device_info {
|
||||||
|
uint8_t model; ///< LiDAR model
|
||||||
|
uint16_t firmware_version; ///< firmware version
|
||||||
|
uint8_t hardware_version; ///< hardare version
|
||||||
|
uint8_t serialnum[16]; ///< serial number
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Health Information
|
||||||
|
struct device_health {
|
||||||
|
uint8_t status; ///< health state
|
||||||
|
uint16_t error_code; ///< error code
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR sampling Rate struct
|
||||||
|
struct sampling_rate {
|
||||||
|
uint8_t rate; ///< sample rate
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR scan frequency struct
|
||||||
|
struct scan_frequency {
|
||||||
|
uint32_t frequency; ///< scan frequency
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
struct scan_rotation {
|
||||||
|
uint8_t rotation;
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Exposure struct
|
||||||
|
struct scan_exposure {
|
||||||
|
uint8_t exposure; ///< low exposure
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Heart beat struct
|
||||||
|
struct scan_heart_beat {
|
||||||
|
uint8_t enable; ///< heart beat
|
||||||
|
} __attribute__((packed));
|
||||||
|
|
||||||
|
struct scan_points {
|
||||||
|
uint8_t flag;
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
struct function_state {
|
||||||
|
uint8_t state;
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR Zero Offset Angle
|
||||||
|
struct offset_angle {
|
||||||
|
int32_t angle;
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR request command packet
|
||||||
|
struct cmd_packet {
|
||||||
|
uint8_t syncByte;
|
||||||
|
uint8_t cmd_flag;
|
||||||
|
uint8_t size;
|
||||||
|
uint8_t data;
|
||||||
|
} __attribute__((packed)) ;
|
||||||
|
|
||||||
|
/// LiDAR response Header
|
||||||
|
struct lidar_ans_header {
|
||||||
|
uint8_t syncByte1;
|
||||||
|
uint8_t syncByte2;
|
||||||
|
uint32_t size: 30;
|
||||||
|
uint32_t subType: 2;
|
||||||
|
uint8_t type;
|
||||||
|
} __attribute__((packed));
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#pragma pack()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief UDP Data format
|
||||||
|
*/
|
||||||
|
typedef struct _dataFrame {
|
||||||
|
uint16_t frameHead;
|
||||||
|
uint8_t deviceType;
|
||||||
|
uint8_t frameType;
|
||||||
|
uint8_t dataIndex;
|
||||||
|
uint8_t frameIndex;
|
||||||
|
uint32_t timestamp;
|
||||||
|
uint8_t headFrameFlag;
|
||||||
|
uint8_t dataFormat;
|
||||||
|
uint8_t disScale;
|
||||||
|
uint32_t startAngle;
|
||||||
|
uint32_t dataNum;
|
||||||
|
uint32_t frameCrc;
|
||||||
|
uint8_t frameBuf[2048];
|
||||||
|
} dataFrame;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @class lidarConfig
|
||||||
|
* @brief Structure containing scan configuration.
|
||||||
|
*
|
||||||
|
* @author jzhang
|
||||||
|
*/
|
||||||
|
typedef struct _lidarConfig {
|
||||||
|
/**
|
||||||
|
* @brief Scanning enable.
|
||||||
|
*/
|
||||||
|
int laser_en;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief rotate enable.
|
||||||
|
*/
|
||||||
|
int motor_en;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief motor RPM.
|
||||||
|
*/
|
||||||
|
int motor_rpm;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief start FOV angle.
|
||||||
|
*/
|
||||||
|
int fov_start;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief end FOV angle.
|
||||||
|
*/
|
||||||
|
int fov_end;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief data receive interface, USB or Ethernet.
|
||||||
|
*/
|
||||||
|
int trans_sel;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief data receive IP.
|
||||||
|
*/
|
||||||
|
char dataRecvIp[16];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief data receive PORT.
|
||||||
|
*/
|
||||||
|
int dataRecvPort;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief device network config, HDCP or Manual.
|
||||||
|
*/
|
||||||
|
int dhcp_en;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief device IP.
|
||||||
|
*/
|
||||||
|
char deviceIp[16];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief device netmask.
|
||||||
|
*/
|
||||||
|
char deviceNetmask[16];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief device gateway ip.
|
||||||
|
*/
|
||||||
|
char deviceGatewayIp[16];
|
||||||
|
|
||||||
|
int laserScanFrequency;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief correction_angle
|
||||||
|
*/
|
||||||
|
int correction_angle;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief correction_distance
|
||||||
|
*/
|
||||||
|
int correction_distance;
|
||||||
|
|
||||||
|
} lidarConfig;
|
||||||
|
|
||||||
|
|
||||||
|
#include "ydlidar_datatype.h"
|
|
@ -0,0 +1,5 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_source_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
|
@ -0,0 +1,297 @@
|
||||||
|
/*********************************************************************
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2008, Willow Garage, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of the Willow Garage nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*********************************************************************/
|
||||||
|
#pragma once
|
||||||
|
#include <algorithm>
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
|
#ifndef M_PI
|
||||||
|
#define M_PI 3.1415926
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace math {
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Convert degrees to radians
|
||||||
|
*/
|
||||||
|
|
||||||
|
static inline double from_degrees(double degrees) {
|
||||||
|
return degrees * M_PI / 180.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Convert radians to degrees
|
||||||
|
*/
|
||||||
|
static inline double to_degrees(double radians) {
|
||||||
|
return radians * 180.0 / M_PI;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief normalize_angle_positive
|
||||||
|
*
|
||||||
|
* Normalizes the angle to be 0 to 2*M_PI
|
||||||
|
* It takes and returns radians.
|
||||||
|
*/
|
||||||
|
static inline double normalize_angle_positive(double angle) {
|
||||||
|
return fmod(fmod(angle, 2.0 * M_PI) + 2.0 * M_PI, 2.0 * M_PI);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief normalize_angle_positive_from_degree
|
||||||
|
*
|
||||||
|
* Normalizes the angle to be 0 to 360
|
||||||
|
* It takes and returns degree.
|
||||||
|
*/
|
||||||
|
static inline double normalize_angle_positive_from_degree(double angle) {
|
||||||
|
double degree = angle;
|
||||||
|
|
||||||
|
while (degree >= 360.0) {
|
||||||
|
degree -= 360.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
while (degree < 0) {
|
||||||
|
degree += 360.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
return degree;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief normalize
|
||||||
|
*
|
||||||
|
* Normalizes the angle to be -M_PI circle to +M_PI circle
|
||||||
|
* It takes and returns radians.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
static inline double normalize_angle(double angle) {
|
||||||
|
double a = normalize_angle_positive(angle);
|
||||||
|
|
||||||
|
if (a > M_PI) {
|
||||||
|
a -= 2.0 * M_PI;
|
||||||
|
}
|
||||||
|
|
||||||
|
return a;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \function
|
||||||
|
* \brief shortest_angular_distance
|
||||||
|
*
|
||||||
|
* Given 2 angles, this returns the shortest angular
|
||||||
|
* difference. The inputs and ouputs are of course radians.
|
||||||
|
*
|
||||||
|
* The result
|
||||||
|
* would always be -pi <= result <= pi. Adding the result
|
||||||
|
* to "from" will always get you an equivelent angle to "to".
|
||||||
|
*/
|
||||||
|
|
||||||
|
static inline double shortest_angular_distance(double from, double to) {
|
||||||
|
return normalize_angle(to - from);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \function
|
||||||
|
*
|
||||||
|
* \brief returns the angle in [-2*M_PI, 2*M_PI] going the other way along the unit circle.
|
||||||
|
* \param angle The angle to which you want to turn in the range [-2*M_PI, 2*M_PI]
|
||||||
|
* E.g. two_pi_complement(-M_PI/4) returns 7_M_PI/4
|
||||||
|
* two_pi_complement(M_PI/4) returns -7*M_PI/4
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
static inline double two_pi_complement(double angle) {
|
||||||
|
//check input conditions
|
||||||
|
if (angle > 2 * M_PI || angle < -2.0 * M_PI) {
|
||||||
|
angle = fmod(angle, 2.0 * M_PI);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (angle < 0) {
|
||||||
|
return (2 * M_PI + angle);
|
||||||
|
} else if (angle > 0) {
|
||||||
|
return (-2 * M_PI + angle);
|
||||||
|
}
|
||||||
|
|
||||||
|
return (2 * M_PI);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \function
|
||||||
|
*
|
||||||
|
* \brief This function is only intended for internal use and not intended for external use. If you do use it, read the documentation very carefully. Returns the min and max amount (in radians) that can be moved from "from" angle to "left_limit" and "right_limit".
|
||||||
|
* \return returns false if "from" angle does not lie in the interval [left_limit,right_limit]
|
||||||
|
* \param from - "from" angle - must lie in [-M_PI, M_PI)
|
||||||
|
* \param left_limit - left limit of valid interval for angular position - must lie in [-M_PI, M_PI], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
|
||||||
|
* \param right_limit - right limit of valid interval for angular position - must lie in [-M_PI, M_PI], left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
|
||||||
|
* \param result_min_delta - minimum (delta) angle (in radians) that can be moved from "from" position before hitting the joint stop
|
||||||
|
* \param result_max_delta - maximum (delta) angle (in radians) that can be movedd from "from" position before hitting the joint stop
|
||||||
|
*/
|
||||||
|
static bool find_min_max_delta(double from, double left_limit,
|
||||||
|
double right_limit, double &result_min_delta, double &result_max_delta) {
|
||||||
|
double delta[4];
|
||||||
|
|
||||||
|
delta[0] = shortest_angular_distance(from, left_limit);
|
||||||
|
delta[1] = shortest_angular_distance(from, right_limit);
|
||||||
|
|
||||||
|
delta[2] = two_pi_complement(delta[0]);
|
||||||
|
delta[3] = two_pi_complement(delta[1]);
|
||||||
|
|
||||||
|
if (fabs(delta[0]) < 1e-6) {
|
||||||
|
result_min_delta = delta[0];
|
||||||
|
result_max_delta = std::max<double>(delta[1], delta[3]);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (fabs(delta[1]) < 1e-6) {
|
||||||
|
result_max_delta = delta[1];
|
||||||
|
result_min_delta = std::min<double>(delta[0], delta[2]);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
double delta_min = delta[0];
|
||||||
|
double delta_min_2pi = delta[2];
|
||||||
|
|
||||||
|
if (delta[2] < delta_min) {
|
||||||
|
delta_min = delta[2];
|
||||||
|
delta_min_2pi = delta[0];
|
||||||
|
}
|
||||||
|
|
||||||
|
double delta_max = delta[1];
|
||||||
|
double delta_max_2pi = delta[3];
|
||||||
|
|
||||||
|
if (delta[3] > delta_max) {
|
||||||
|
delta_max = delta[3];
|
||||||
|
delta_max_2pi = delta[1];
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// printf("%f %f %f %f\n",delta_min,delta_min_2pi,delta_max,delta_max_2pi);
|
||||||
|
if ((delta_min <= delta_max_2pi) || (delta_max >= delta_min_2pi)) {
|
||||||
|
result_min_delta = delta_max_2pi;
|
||||||
|
result_max_delta = delta_min_2pi;
|
||||||
|
|
||||||
|
if (left_limit == -M_PI && right_limit == M_PI) {
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
result_min_delta = delta_min;
|
||||||
|
result_max_delta = delta_max;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \function
|
||||||
|
*
|
||||||
|
* \brief Returns the delta from "from_angle" to "to_angle" making sure it does not violate limits specified by left_limit and right_limit.
|
||||||
|
* The valid interval of angular positions is [left_limit,right_limit]. E.g., [-0.25,0.25] is a 0.5 radians wide interval that contains 0.
|
||||||
|
* But [0.25,-0.25] is a 2*M_PI-0.5 wide interval that contains M_PI (but not 0).
|
||||||
|
* The value of shortest_angle is the angular difference between "from" and "to" that lies within the defined valid interval.
|
||||||
|
* E.g. shortest_angular_distance_with_limits(-0.5,0.5,0.25,-0.25,ss) evaluates ss to 2*M_PI-1.0 and returns true while
|
||||||
|
* shortest_angular_distance_with_limits(-0.5,0.5,-0.25,0.25,ss) returns false since -0.5 and 0.5 do not lie in the interval [-0.25,0.25]
|
||||||
|
*
|
||||||
|
* \return true if "from" and "to" positions are within the limit interval, false otherwise
|
||||||
|
* \param from - "from" angle
|
||||||
|
* \param to - "to" angle
|
||||||
|
* \param left_limit - left limit of valid interval for angular position, left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
|
||||||
|
* \param right_limit - right limit of valid interval for angular position, left and right limits are specified on the unit circle w.r.t to a reference pointing inwards
|
||||||
|
* \param shortest_angle - result of the shortest angle calculation
|
||||||
|
*/
|
||||||
|
static inline bool shortest_angular_distance_with_limits(double from, double to,
|
||||||
|
double left_limit, double right_limit, double &shortest_angle) {
|
||||||
|
|
||||||
|
double min_delta = -2 * M_PI;
|
||||||
|
double max_delta = 2 * M_PI;
|
||||||
|
double min_delta_to = -2 * M_PI;
|
||||||
|
double max_delta_to = 2 * M_PI;
|
||||||
|
bool flag = find_min_max_delta(from, left_limit, right_limit, min_delta,
|
||||||
|
max_delta);
|
||||||
|
double delta = shortest_angular_distance(from, to);
|
||||||
|
double delta_mod_2pi = two_pi_complement(delta);
|
||||||
|
|
||||||
|
|
||||||
|
if (flag) { //from position is within the limits
|
||||||
|
if (delta >= min_delta && delta <= max_delta) {
|
||||||
|
shortest_angle = delta;
|
||||||
|
return true;
|
||||||
|
} else if (delta_mod_2pi >= min_delta && delta_mod_2pi <= max_delta) {
|
||||||
|
shortest_angle = delta_mod_2pi;
|
||||||
|
return true;
|
||||||
|
} else { //to position is outside the limits
|
||||||
|
find_min_max_delta(to, left_limit, right_limit, min_delta_to, max_delta_to);
|
||||||
|
|
||||||
|
if (fabs(min_delta_to) < fabs(max_delta_to)) {
|
||||||
|
shortest_angle = std::max<double>(delta, delta_mod_2pi);
|
||||||
|
} else if (fabs(min_delta_to) > fabs(max_delta_to)) {
|
||||||
|
shortest_angle = std::min<double>(delta, delta_mod_2pi);
|
||||||
|
} else {
|
||||||
|
if (fabs(delta) < fabs(delta_mod_2pi)) {
|
||||||
|
shortest_angle = delta;
|
||||||
|
} else {
|
||||||
|
shortest_angle = delta_mod_2pi;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else { // from position is outside the limits
|
||||||
|
find_min_max_delta(to, left_limit, right_limit, min_delta_to, max_delta_to);
|
||||||
|
|
||||||
|
if (fabs(min_delta) < fabs(max_delta)) {
|
||||||
|
shortest_angle = std::min<double>(delta, delta_mod_2pi);
|
||||||
|
} else if (fabs(min_delta) > fabs(max_delta)) {
|
||||||
|
shortest_angle = std::max<double>(delta, delta_mod_2pi);
|
||||||
|
} else {
|
||||||
|
if (fabs(delta) < fabs(delta_mod_2pi)) {
|
||||||
|
shortest_angle = delta;
|
||||||
|
} else {
|
||||||
|
shortest_angle = delta_mod_2pi;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
shortest_angle = delta;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}// namespace math
|
||||||
|
}// namespace core
|
||||||
|
}// namespace ydlidar
|
|
@ -0,0 +1,302 @@
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* CActiveSocket.cpp - Active Socket Implementation */
|
||||||
|
/* */
|
||||||
|
/* Author : Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2007-2009 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#include "ActiveSocket.h"
|
||||||
|
|
||||||
|
using namespace ydlidar;
|
||||||
|
using namespace ydlidar::core;
|
||||||
|
using namespace ydlidar::core::network;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
CActiveSocket::CActiveSocket(CSocketType nType) : CSimpleSocket(nType) {
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// ConnectTCP() -
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
bool CActiveSocket::ConnectTCP(const char *pAddr, uint16_t nPort) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
struct in_addr stIpAddress;
|
||||||
|
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Preconnection setup that must be preformed
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
memset(&m_stServerSockaddr, 0, sizeof(m_stServerSockaddr));
|
||||||
|
m_stServerSockaddr.sin_family = AF_INET;
|
||||||
|
|
||||||
|
if ((m_pHE = GETHOSTBYNAME(pAddr)) == NULL) {
|
||||||
|
#if defined(_WIN32)
|
||||||
|
TranslateSocketError();
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (h_errno == HOST_NOT_FOUND) {
|
||||||
|
SetSocketError(SocketInvalidAddress);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(&stIpAddress, m_pHE->h_addr_list[0], m_pHE->h_length);
|
||||||
|
m_stServerSockaddr.sin_addr.s_addr = stIpAddress.s_addr;
|
||||||
|
|
||||||
|
if ((int32_t)m_stServerSockaddr.sin_addr.s_addr == CSimpleSocket::SocketError) {
|
||||||
|
TranslateSocketError();
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_stServerSockaddr.sin_port = htons(nPort);
|
||||||
|
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Connect to address "xxx.xxx.xxx.xxx" (IPv4) address only.
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
if (connect(m_socket, (struct sockaddr *)&m_stServerSockaddr,
|
||||||
|
sizeof(m_stServerSockaddr)) ==
|
||||||
|
CSimpleSocket::SocketError) {
|
||||||
|
//--------------------------------------------------------------
|
||||||
|
// Get error value this might be a non-blocking socket so we
|
||||||
|
// must first check.
|
||||||
|
//--------------------------------------------------------------
|
||||||
|
TranslateSocketError();
|
||||||
|
|
||||||
|
//--------------------------------------------------------------
|
||||||
|
// If the socket is non-blocking and the current socket error
|
||||||
|
// is SocketEinprogress or SocketEwouldblock then poll connection
|
||||||
|
// with select for designated timeout period.
|
||||||
|
// Linux returns EINPROGRESS and Windows returns WSAEWOULDBLOCK.
|
||||||
|
//--------------------------------------------------------------
|
||||||
|
if ((IsNonblocking()) &&
|
||||||
|
((GetSocketError() == CSimpleSocket::SocketEwouldblock) ||
|
||||||
|
(GetSocketError() == CSimpleSocket::SocketEinprogress))) {
|
||||||
|
bRetVal = Select(GetConnectTimeoutSec(), GetConnectTimeoutUSec());
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
TranslateSocketError();
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// ConnectUDP() -
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
bool CActiveSocket::ConnectUDP(const char *pAddr, uint16_t nPort) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
struct in_addr stIpAddress;
|
||||||
|
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Pre-connection setup that must be preformed
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
memset(&m_stServerSockaddr, 0, sizeof(m_stServerSockaddr));
|
||||||
|
m_stServerSockaddr.sin_family = AF_INET;
|
||||||
|
|
||||||
|
if ((m_pHE = GETHOSTBYNAME(pAddr)) == NULL) {
|
||||||
|
#if defined(_WIN32)
|
||||||
|
TranslateSocketError();
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (h_errno == HOST_NOT_FOUND) {
|
||||||
|
SetSocketError(SocketInvalidAddress);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(&stIpAddress, m_pHE->h_addr_list[0], m_pHE->h_length);
|
||||||
|
m_stServerSockaddr.sin_addr.s_addr = stIpAddress.s_addr;
|
||||||
|
|
||||||
|
if ((int32_t)m_stServerSockaddr.sin_addr.s_addr == CSimpleSocket::SocketError) {
|
||||||
|
TranslateSocketError();
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_stServerSockaddr.sin_port = htons(nPort);
|
||||||
|
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Connect to address "xxx.xxx.xxx.xxx" (IPv4) address only.
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
if (connect(m_socket, (struct sockaddr *)&m_stServerSockaddr,
|
||||||
|
sizeof(m_stServerSockaddr)) != CSimpleSocket::SocketError) {
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TranslateSocketError();
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// ConnectRAW() -
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
bool CActiveSocket::ConnectRAW(const char *pAddr, uint16_t nPort) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
struct in_addr stIpAddress;
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Pre-connection setup that must be preformed
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
memset(&m_stServerSockaddr, 0, sizeof(m_stServerSockaddr));
|
||||||
|
m_stServerSockaddr.sin_family = AF_INET;
|
||||||
|
|
||||||
|
if ((m_pHE = GETHOSTBYNAME(pAddr)) == NULL) {
|
||||||
|
#if defined(_WIN32)
|
||||||
|
TranslateSocketError();
|
||||||
|
#else
|
||||||
|
|
||||||
|
if (h_errno == HOST_NOT_FOUND) {
|
||||||
|
SetSocketError(SocketInvalidAddress);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(&stIpAddress, m_pHE->h_addr_list[0], m_pHE->h_length);
|
||||||
|
m_stServerSockaddr.sin_addr.s_addr = stIpAddress.s_addr;
|
||||||
|
|
||||||
|
if ((int32_t)m_stServerSockaddr.sin_addr.s_addr == CSimpleSocket::SocketError) {
|
||||||
|
TranslateSocketError();
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_stServerSockaddr.sin_port = htons(nPort);
|
||||||
|
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
// Connect to address "xxx.xxx.xxx.xxx" (IPv4) address only.
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
if (connect(m_socket, (struct sockaddr *)&m_stServerSockaddr,
|
||||||
|
sizeof(m_stServerSockaddr)) != CSimpleSocket::SocketError) {
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
TranslateSocketError();
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// Open() - Create a connection to a specified address on a specified port
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
bool CActiveSocket::Open(const char *pAddr, uint16_t nPort) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
|
||||||
|
if (IsSocketValid() == false) {
|
||||||
|
SetSocketError(CSimpleSocket::SocketInvalidSocket);
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pAddr == NULL) {
|
||||||
|
SetSocketError(CSimpleSocket::SocketInvalidAddress);
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (nPort == 0) {
|
||||||
|
SetSocketError(CSimpleSocket::SocketInvalidPort);
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (m_nSocketType) {
|
||||||
|
case CSimpleSocket::SocketTypeTcp : {
|
||||||
|
bRetVal = ConnectTCP(pAddr, nPort);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case CSimpleSocket::SocketTypeUdp : {
|
||||||
|
bRetVal = ConnectUDP(pAddr, nPort);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case CSimpleSocket::SocketTypeRaw :
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// If successful then create a local copy of the address and port
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if (bRetVal) {
|
||||||
|
socklen_t nSockLen = sizeof(struct sockaddr);
|
||||||
|
|
||||||
|
memset(&m_stServerSockaddr, 0, nSockLen);
|
||||||
|
getpeername(m_socket, (struct sockaddr *)&m_stServerSockaddr, &nSockLen);
|
||||||
|
|
||||||
|
nSockLen = sizeof(struct sockaddr);
|
||||||
|
memset(&m_stClientSockaddr, 0, nSockLen);
|
||||||
|
getsockname(m_socket, (struct sockaddr *)&m_stClientSockaddr, &nSockLen);
|
||||||
|
|
||||||
|
SetSocketError(SocketSuccess);
|
||||||
|
}
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
|
@ -0,0 +1,100 @@
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* ActiveSocket.h - Active Socket Decleration */
|
||||||
|
/* */
|
||||||
|
/* Author : Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2007-2009 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#ifndef __ACTIVESOCKET_H__
|
||||||
|
#define __ACTIVESOCKET_H__
|
||||||
|
|
||||||
|
#include "SimpleSocket.h"
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace network {
|
||||||
|
|
||||||
|
class CPassiveSocket;
|
||||||
|
|
||||||
|
/// Provides a platform independent class to create an active socket.
|
||||||
|
/// An active socket is used to create a socket which connects to a server.
|
||||||
|
/// This type of object would be used when an application needs to send/receive
|
||||||
|
/// data from a server.
|
||||||
|
class CActiveSocket : public CSimpleSocket {
|
||||||
|
public:
|
||||||
|
friend class CPassiveSocket;
|
||||||
|
|
||||||
|
explicit CActiveSocket(CSocketType type = SocketTypeTcp);
|
||||||
|
virtual ~CActiveSocket() {
|
||||||
|
Close();
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Established a connection to the address specified by pAddr.
|
||||||
|
/// Connection-based protocol sockets (CSocket::SocketTypeTcp) may
|
||||||
|
/// successfully call open() only once, however; connectionless protocol
|
||||||
|
/// sockets (CSocket::SocketTypeUdp) may use Open() multiple times to
|
||||||
|
/// change their association.
|
||||||
|
/// @param pAddr specifies the destination address to connect.
|
||||||
|
/// @param nPort specifies the destination port.
|
||||||
|
/// @return true if successful connection made, otherwise false.
|
||||||
|
virtual bool Open(const char *pAddr, uint16_t nPort);
|
||||||
|
|
||||||
|
private:
|
||||||
|
/// Utility function used to create a TCP connection, called from Open().
|
||||||
|
/// @return true if successful connection made, otherwise false.
|
||||||
|
bool ConnectTCP(const char *pAddr, uint16_t nPort);
|
||||||
|
|
||||||
|
/// Utility function used to create a UDP connection, called from Open().
|
||||||
|
/// @return true if successful connection made, otherwise false.
|
||||||
|
bool ConnectUDP(const char *pAddr, uint16_t nPort);
|
||||||
|
|
||||||
|
/// Utility function used to create a RAW connection, called from Open().
|
||||||
|
/// @return true if successful connection made, otherwise false.
|
||||||
|
bool ConnectRAW(const char *pAddr, uint16_t nPort);
|
||||||
|
|
||||||
|
private:
|
||||||
|
struct hostent *m_pHE;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
}//namespace socket
|
||||||
|
}//namespace core
|
||||||
|
}//namespace ydlidar
|
||||||
|
|
||||||
|
#endif /* __ACTIVESOCKET_H__ */
|
||||||
|
|
|
@ -0,0 +1,10 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_source_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
||||||
|
IF (WIN32)
|
||||||
|
add_to_ydlidar_libraries(setupapi ws2_32)
|
||||||
|
ELSE()
|
||||||
|
add_to_ydlidar_libraries(rt)
|
||||||
|
ENDIF()
|
|
@ -0,0 +1,315 @@
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* PassiveSocket.cpp - Passive Socket Implementation */
|
||||||
|
/* */
|
||||||
|
/* Author : Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2007-2009 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#include "PassiveSocket.h"
|
||||||
|
|
||||||
|
using namespace ydlidar;
|
||||||
|
using namespace ydlidar::core;
|
||||||
|
using namespace ydlidar::core::network;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
CPassiveSocket::CPassiveSocket(CSocketType nType) : CSimpleSocket(nType) {
|
||||||
|
}
|
||||||
|
|
||||||
|
bool CPassiveSocket::BindMulticast(const char *pInterface, const char *pGroup,
|
||||||
|
uint16_t nPort) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
#if defined(_WIN32)
|
||||||
|
ULONG inAddr;
|
||||||
|
#else
|
||||||
|
int32_t nReuse;
|
||||||
|
in_addr_t inAddr;
|
||||||
|
|
||||||
|
nReuse = IPTOS_LOWDELAY;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// Set the following socket option SO_REUSEADDR. This will allow the file
|
||||||
|
// descriptor to be reused immediately after the socket is closed instead
|
||||||
|
// of setting in a TIMED_WAIT state.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
memset(&m_stMulticastGroup, 0, sizeof(m_stMulticastGroup));
|
||||||
|
m_stMulticastGroup.sin_family = AF_INET;
|
||||||
|
m_stMulticastGroup.sin_port = htons(nPort);
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// If no IP Address (interface ethn) is supplied, or the loop back is
|
||||||
|
// specified then bind to any interface, else bind to specified interface.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if ((pInterface == NULL) || (!strlen(pInterface))) {
|
||||||
|
m_stMulticastGroup.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||||
|
} else {
|
||||||
|
if ((inAddr = inet_addr(pInterface)) != INADDR_NONE) {
|
||||||
|
m_stMulticastGroup.sin_addr.s_addr = inAddr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// Bind to the specified port
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if (bind(m_socket, (struct sockaddr *)&m_stMulticastGroup,
|
||||||
|
sizeof(m_stMulticastGroup)) == 0) {
|
||||||
|
//----------------------------------------------------------------------
|
||||||
|
// Join the multicast group
|
||||||
|
//----------------------------------------------------------------------
|
||||||
|
m_stMulticastRequest.imr_multiaddr.s_addr = inet_addr(pGroup);
|
||||||
|
m_stMulticastRequest.imr_interface.s_addr = m_stMulticastGroup.sin_addr.s_addr;
|
||||||
|
|
||||||
|
if (SETSOCKOPT(m_socket, IPPROTO_IP, IP_ADD_MEMBERSHIP,
|
||||||
|
(void *)&m_stMulticastRequest,
|
||||||
|
sizeof(m_stMulticastRequest)) == CSimpleSocket::SocketSuccess) {
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
}
|
||||||
|
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// If there was a socket error then close the socket to clean out the
|
||||||
|
// connection in the backlog.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
TranslateSocketError();
|
||||||
|
|
||||||
|
if (bRetVal == false) {
|
||||||
|
Close();
|
||||||
|
}
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// Listen() -
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
bool CPassiveSocket::Listen(const char *pAddr, uint16_t nPort,
|
||||||
|
int32_t nConnectionBacklog) {
|
||||||
|
bool bRetVal = false;
|
||||||
|
#if defined(_WIN32)
|
||||||
|
ULONG inAddr;
|
||||||
|
#else
|
||||||
|
int32_t nReuse;
|
||||||
|
in_addr_t inAddr;
|
||||||
|
|
||||||
|
nReuse = IPTOS_LOWDELAY;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// Set the following socket option SO_REUSEADDR. This will allow the file
|
||||||
|
// descriptor to be reused immediately after the socket is closed instead
|
||||||
|
// of setting in a TIMED_WAIT state.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
#if defined(__linux__)
|
||||||
|
SETSOCKOPT(m_socket, SOL_SOCKET, SO_REUSEADDR, (char *)&nReuse,
|
||||||
|
sizeof(int32_t));
|
||||||
|
SETSOCKOPT(m_socket, IPPROTO_TCP, IP_TOS, &nReuse, sizeof(int32_t));
|
||||||
|
#endif
|
||||||
|
|
||||||
|
memset(&m_stServerSockaddr, 0, sizeof(m_stServerSockaddr));
|
||||||
|
m_stServerSockaddr.sin_family = AF_INET;
|
||||||
|
m_stServerSockaddr.sin_port = htons(nPort);
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// If no IP Address (interface ethn) is supplied, or the loop back is
|
||||||
|
// specified then bind to any interface, else bind to specified interface.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if ((pAddr == NULL) || (!strlen(pAddr))) {
|
||||||
|
m_stServerSockaddr.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||||
|
} else {
|
||||||
|
if ((inAddr = inet_addr(pAddr)) != INADDR_NONE) {
|
||||||
|
m_stServerSockaddr.sin_addr.s_addr = inAddr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// Bind to the specified port
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if (bind(m_socket, (struct sockaddr *)&m_stServerSockaddr,
|
||||||
|
sizeof(m_stServerSockaddr)) != CSimpleSocket::SocketError) {
|
||||||
|
if (m_nSocketType == CSimpleSocket::SocketTypeTcp) {
|
||||||
|
if (listen(m_socket, nConnectionBacklog) != CSimpleSocket::SocketError) {
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
bRetVal = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// If there was a socket error then close the socket to clean out the
|
||||||
|
// connection in the backlog.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
TranslateSocketError();
|
||||||
|
|
||||||
|
if (bRetVal == false) {
|
||||||
|
CSocketError err = GetSocketError();
|
||||||
|
Close();
|
||||||
|
SetSocketError(err);
|
||||||
|
}
|
||||||
|
|
||||||
|
return bRetVal;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// Accept() -
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
CActiveSocket *CPassiveSocket::Accept() {
|
||||||
|
uint32_t nSockLen;
|
||||||
|
CActiveSocket *pClientSocket = NULL;
|
||||||
|
SOCKET socket = CSimpleSocket::SocketError;
|
||||||
|
|
||||||
|
if (m_nSocketType != CSimpleSocket::SocketTypeTcp) {
|
||||||
|
SetSocketError(CSimpleSocket::SocketProtocolError);
|
||||||
|
return pClientSocket;
|
||||||
|
}
|
||||||
|
|
||||||
|
pClientSocket = new CActiveSocket();
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
// Wait for incoming connection.
|
||||||
|
//--------------------------------------------------------------------------
|
||||||
|
if (pClientSocket != NULL) {
|
||||||
|
CSocketError socketErrno = SocketSuccess;
|
||||||
|
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
nSockLen = sizeof(m_stClientSockaddr);
|
||||||
|
|
||||||
|
do {
|
||||||
|
errno = 0;
|
||||||
|
socket = accept(m_socket, (struct sockaddr *)&m_stClientSockaddr,
|
||||||
|
(socklen_t *)&nSockLen);
|
||||||
|
|
||||||
|
if (socket != -1) {
|
||||||
|
pClientSocket->SetSocketHandle(socket);
|
||||||
|
pClientSocket->TranslateSocketError();
|
||||||
|
socketErrno = pClientSocket->GetSocketError();
|
||||||
|
socklen_t nSockLen = sizeof(struct sockaddr);
|
||||||
|
|
||||||
|
//-------------------------------------------------------------
|
||||||
|
// Store client and server IP and port information for this
|
||||||
|
// connection.
|
||||||
|
//-------------------------------------------------------------
|
||||||
|
getpeername(m_socket, (struct sockaddr *)&pClientSocket->m_stClientSockaddr,
|
||||||
|
&nSockLen);
|
||||||
|
memcpy((void *)&pClientSocket->m_stClientSockaddr, (void *)&m_stClientSockaddr,
|
||||||
|
nSockLen);
|
||||||
|
|
||||||
|
memset(&pClientSocket->m_stServerSockaddr, 0, nSockLen);
|
||||||
|
getsockname(m_socket, (struct sockaddr *)&pClientSocket->m_stServerSockaddr,
|
||||||
|
&nSockLen);
|
||||||
|
} else {
|
||||||
|
TranslateSocketError();
|
||||||
|
socketErrno = GetSocketError();
|
||||||
|
}
|
||||||
|
|
||||||
|
} while (socketErrno == CSimpleSocket::SocketInterrupted);
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
if (socketErrno != CSimpleSocket::SocketSuccess) {
|
||||||
|
delete pClientSocket;
|
||||||
|
pClientSocket = NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return pClientSocket;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
//
|
||||||
|
// Send() - Send data on a valid socket
|
||||||
|
//
|
||||||
|
//------------------------------------------------------------------------------
|
||||||
|
int32_t CPassiveSocket::Send(const uint8_t *pBuf, size_t bytesToSend) {
|
||||||
|
SetSocketError(SocketSuccess);
|
||||||
|
m_nBytesSent = 0;
|
||||||
|
|
||||||
|
switch (m_nSocketType) {
|
||||||
|
case CSimpleSocket::SocketTypeUdp: {
|
||||||
|
if (IsSocketValid()) {
|
||||||
|
if ((bytesToSend > 0) && (pBuf != NULL)) {
|
||||||
|
m_timer.Initialize();
|
||||||
|
m_timer.SetStartTime();
|
||||||
|
|
||||||
|
m_nBytesSent = SENDTO(m_socket, pBuf, bytesToSend, 0,
|
||||||
|
(const sockaddr *)&m_stClientSockaddr,
|
||||||
|
sizeof(m_stClientSockaddr));
|
||||||
|
|
||||||
|
m_timer.SetEndTime();
|
||||||
|
|
||||||
|
if (m_nBytesSent == CSimpleSocket::SocketError) {
|
||||||
|
TranslateSocketError();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case CSimpleSocket::SocketTypeTcp:
|
||||||
|
CSimpleSocket::Send(pBuf, bytesToSend);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
SetSocketError(SocketProtocolError);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return m_nBytesSent;
|
||||||
|
}
|
|
@ -0,0 +1,128 @@
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* Socket.h - Passive Socket Decleration. */
|
||||||
|
/* */
|
||||||
|
/* Author : Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2007-2009 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#ifndef __PASSIVESOCKET_H__
|
||||||
|
#define __PASSIVESOCKET_H__
|
||||||
|
#include "ActiveSocket.h"
|
||||||
|
|
||||||
|
/// Provides a platform independent class to create a passive socket.
|
||||||
|
/// A passive socket is used to create a "listening" socket. This type
|
||||||
|
/// of object would be used when an application needs to wait for
|
||||||
|
/// inbound connections. Support for CSimpleSocket::SocketTypeTcp,
|
||||||
|
/// CSimpleSocket::SocketTypeUdp, and CSimpleSocket::SocketTypeRaw is handled
|
||||||
|
/// in a similar fashion. The big difference is that the method
|
||||||
|
/// CPassiveSocket::Accept should not be called on the latter two socket
|
||||||
|
/// types.
|
||||||
|
///
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace network {
|
||||||
|
|
||||||
|
class CPassiveSocket : public CSimpleSocket {
|
||||||
|
public:
|
||||||
|
explicit CPassiveSocket(CSocketType type = SocketTypeTcp);
|
||||||
|
virtual ~CPassiveSocket() {
|
||||||
|
Close();
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Extracts the first connection request on the queue of pending
|
||||||
|
/// connections and creates a newly connected socket. Used with
|
||||||
|
/// CSocketType CSimpleSocket::SocketTypeTcp. It is the responsibility of
|
||||||
|
/// the caller to delete the returned object when finished.
|
||||||
|
/// @return if successful a pointer to a newly created CActiveSocket object
|
||||||
|
/// will be returned and the internal error condition of the CPassiveSocket
|
||||||
|
/// object will be CPassiveSocket::SocketSuccess. If an error condition was encountered
|
||||||
|
/// the NULL will be returned and one of the following error conditions will be set:
|
||||||
|
/// CPassiveSocket::SocketEwouldblock, CPassiveSocket::SocketInvalidSocket,
|
||||||
|
/// CPassiveSocket::SocketConnectionAborted, CPassiveSocket::SocketInterrupted
|
||||||
|
/// CPassiveSocket::SocketProtocolError, CPassiveSocket::SocketFirewallError
|
||||||
|
virtual CActiveSocket *Accept(void);
|
||||||
|
|
||||||
|
/// Bind to a multicast group on a specified interface, multicast group, and port
|
||||||
|
///
|
||||||
|
/// @param pInterface - interface on which to bind.
|
||||||
|
/// @param pGroup - multicast group address to bind.
|
||||||
|
/// @param nPort - port on which multicast
|
||||||
|
/// @return true if able to bind to interface and multicast group.
|
||||||
|
/// If not successful, the false is returned and one of the following error
|
||||||
|
/// condiitions will be set: CPassiveSocket::SocketAddressInUse, CPassiveSocket::SocketProtocolError,
|
||||||
|
/// CPassiveSocket::SocketInvalidSocket. The following socket errors are for Linux/Unix
|
||||||
|
/// derived systems only: CPassiveSocket::SocketInvalidSocketBuffer
|
||||||
|
bool BindMulticast(const char *pInterface, const char *pGroup, uint16_t nPort);
|
||||||
|
|
||||||
|
/// Create a listening socket at local ip address 'x.x.x.x' or 'localhost'
|
||||||
|
/// if pAddr is NULL on port nPort.
|
||||||
|
///
|
||||||
|
/// @param pAddr specifies the IP address on which to listen.
|
||||||
|
/// @param nPort specifies the port on which to listen.
|
||||||
|
/// @param nConnectionBacklog specifies connection queue backlog (default 30,000)
|
||||||
|
/// @return true if a listening socket was created.
|
||||||
|
/// If not successful, the false is returned and one of the following error
|
||||||
|
/// conditions will be set: CPassiveSocket::SocketAddressInUse, CPassiveSocket::SocketProtocolError,
|
||||||
|
/// CPassiveSocket::SocketInvalidSocket. The following socket errors are for Linux/Unix
|
||||||
|
/// derived systems only: CPassiveSocket::SocketInvalidSocketBuffer
|
||||||
|
virtual bool Listen(const char *pAddr, uint16_t nPort,
|
||||||
|
int32_t nConnectionBacklog = 30000);
|
||||||
|
|
||||||
|
/// Attempts to send a block of data on an established connection.
|
||||||
|
/// @param pBuf block of data to be sent.
|
||||||
|
/// @param bytesToSend size of data block to be sent.
|
||||||
|
/// @return number of bytes actually sent, return of zero means the
|
||||||
|
/// connection has been shutdown on the other side, and a return of -1
|
||||||
|
/// means that an error has occurred. If an error was signaled then one
|
||||||
|
/// of the following error codes will be set: CPassiveSocket::SocketInvalidSocket,
|
||||||
|
/// CPassiveSocket::SocketEwouldblock, SimpleSocket::SocketConnectionReset,
|
||||||
|
/// CPassiveSocket::SocketInvalidSocketBuffer, CPassiveSocket::SocketInterrupted,
|
||||||
|
/// CPassiveSocket::SocketProtocolError, CPassiveSocket::SocketNotconnected
|
||||||
|
/// <br>\b Note: This function is used only for a socket of type
|
||||||
|
/// CSimpleSocket::SocketTypeUdp
|
||||||
|
virtual int32_t Send(const uint8_t *pBuf, size_t bytesToSend);
|
||||||
|
|
||||||
|
private:
|
||||||
|
struct ip_mreq m_stMulticastRequest; /// group address for multicast
|
||||||
|
|
||||||
|
};
|
||||||
|
}//namespace socket
|
||||||
|
}//namespace core
|
||||||
|
}// namespace ydlidar
|
||||||
|
|
||||||
|
#endif // __PASSIVESOCKET_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,691 @@
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* SimpleSocket.h - Simple Socket base class decleration. */
|
||||||
|
/* */
|
||||||
|
/* Author : Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2007-2009 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#ifndef __SOCKET_H__
|
||||||
|
#define __SOCKET_H__
|
||||||
|
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#include <thread>
|
||||||
|
#include <chrono>
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(__linux__) || defined (_DARWIN)
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <netinet/in.h>
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
#include <netinet/tcp.h>
|
||||||
|
#include <netinet/ip.h>
|
||||||
|
#include <netdb.h>
|
||||||
|
#endif
|
||||||
|
#ifdef __linux__
|
||||||
|
#include <linux/if_packet.h>
|
||||||
|
#include <linux/if_ether.h>
|
||||||
|
#include <linux/if.h>
|
||||||
|
#include <sys/sendfile.h>
|
||||||
|
#endif
|
||||||
|
#ifdef _DARWIN
|
||||||
|
#include <net/if.h>
|
||||||
|
#endif
|
||||||
|
#if defined(__linux__) || defined (_DARWIN)
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <sys/uio.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include <io.h>
|
||||||
|
#include <winsock2.h>
|
||||||
|
#include <Ws2tcpip.h>
|
||||||
|
|
||||||
|
#pragma warning(disable: 4786)
|
||||||
|
#pragma comment(lib, "ws2_32.lib")
|
||||||
|
#pragma comment(lib, "setupapi.lib")
|
||||||
|
#define IPTOS_LOWDELAY 0x10
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#include "StatTimer.h"
|
||||||
|
#include <core/common/ChannelDevice.h>
|
||||||
|
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// General class macro definitions and typedefs
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
#ifndef INVALID_SOCKET
|
||||||
|
#define INVALID_SOCKET ~(0)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define SOCKET_SENDFILE_BLOCKSIZE 8192
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
using namespace common;
|
||||||
|
namespace network {
|
||||||
|
|
||||||
|
|
||||||
|
/// Provides a platform independent class to for socket development.
|
||||||
|
/// This class is designed to abstract socket communication development in a
|
||||||
|
/// platform independent manner.
|
||||||
|
/// - Socket types
|
||||||
|
/// -# CActiveSocket Class
|
||||||
|
/// -# CPassiveSocket Class
|
||||||
|
class CSimpleSocket : public ChannelDevice {
|
||||||
|
public:
|
||||||
|
/// Defines the three possible states for shuting down a socket.
|
||||||
|
typedef enum {
|
||||||
|
Receives = SHUT_RD, ///< Shutdown passive socket.
|
||||||
|
Sends = SHUT_WR, ///< Shutdown active socket.
|
||||||
|
Both = SHUT_RDWR ///< Shutdown both active and passive sockets.
|
||||||
|
} CShutdownMode;
|
||||||
|
|
||||||
|
/// Defines the socket types defined by CSimpleSocket class.
|
||||||
|
typedef enum {
|
||||||
|
SocketTypeInvalid = 0, ///< Invalid socket type.
|
||||||
|
SocketTypeTcp, ///< Defines socket as TCP socket.
|
||||||
|
SocketTypeUdp, ///< Defines socket as UDP socket.
|
||||||
|
SocketTypeTcp6, ///< Defines socket as IPv6 TCP socket.
|
||||||
|
SocketTypeUdp6, ///< Defines socket as IPv6 UDP socket.
|
||||||
|
SocketTypeRaw ///< Provides raw network protocol access.
|
||||||
|
} CSocketType;
|
||||||
|
|
||||||
|
/// Defines all error codes handled by the CSimpleSocket class.
|
||||||
|
typedef enum {
|
||||||
|
SocketError = -1, ///< Generic socket error translates to error below.
|
||||||
|
SocketSuccess = 0, ///< No socket error.
|
||||||
|
SocketInvalidSocket, ///< Invalid socket handle.
|
||||||
|
SocketInvalidAddress, ///< Invalid destination address specified.
|
||||||
|
SocketInvalidPort, ///< Invalid destination port specified.
|
||||||
|
SocketConnectionRefused, ///< No server is listening at remote address.
|
||||||
|
SocketTimedout, ///< Timed out while attempting operation.
|
||||||
|
SocketEwouldblock, ///< Operation would block if socket were blocking.
|
||||||
|
SocketNotconnected, ///< Currently not connected.
|
||||||
|
SocketEinprogress, ///< Socket is non-blocking and the connection cannot be completed immediately
|
||||||
|
SocketInterrupted, ///< Call was interrupted by a signal that was caught before a valid connection arrived.
|
||||||
|
SocketConnectionAborted, ///< The connection has been aborted.
|
||||||
|
SocketProtocolError, ///< Invalid protocol for operation.
|
||||||
|
SocketFirewallError, ///< Firewall rules forbid connection.
|
||||||
|
SocketInvalidSocketBuffer, ///< The receive buffer point outside the process's address space.
|
||||||
|
SocketConnectionReset, ///< Connection was forcibly closed by the remote host.
|
||||||
|
SocketAddressInUse, ///< Address already in use.
|
||||||
|
SocketInvalidPointer, ///< Pointer type supplied as argument is invalid.
|
||||||
|
SocketEunknown ///< Unknown error please report to mark@carrierlabs.com
|
||||||
|
} CSocketError;
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit CSimpleSocket(CSocketType type = SocketTypeTcp);
|
||||||
|
explicit CSimpleSocket(CSimpleSocket &socket);
|
||||||
|
|
||||||
|
virtual ~CSimpleSocket() {
|
||||||
|
if (m_pBuffer != NULL) {
|
||||||
|
delete [] m_pBuffer;
|
||||||
|
m_pBuffer = NULL;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
static void WSACleanUp();
|
||||||
|
|
||||||
|
|
||||||
|
/// Initialize instance of CSocket. This method MUST be called before an
|
||||||
|
/// object can be used. Errors : CSocket::SocketProtocolError,
|
||||||
|
/// CSocket::SocketInvalidSocket,
|
||||||
|
/// @return true if properly initialized.
|
||||||
|
virtual bool Initialize(void);
|
||||||
|
|
||||||
|
/// Close socket
|
||||||
|
/// @return true if successfully closed otherwise returns false.
|
||||||
|
virtual bool Close(void);
|
||||||
|
|
||||||
|
/// Shutdown shut down socket send and receive operations
|
||||||
|
/// CShutdownMode::Receives - Disables further receive operations.
|
||||||
|
/// CShutdownMode::Sends - Disables further send operations.
|
||||||
|
/// CShutdownBoth:: - Disables further send and receive operations.
|
||||||
|
/// @param nShutdown specifies the type of shutdown.
|
||||||
|
/// @return true if successfully shutdown otherwise returns false.
|
||||||
|
virtual bool Shutdown(CShutdownMode nShutdown);
|
||||||
|
|
||||||
|
/// Examine the socket descriptor sets currently owned by the instance of
|
||||||
|
/// the socket class (the readfds, writefds, and errorfds parameters) to
|
||||||
|
/// see whether some of their descriptors are ready for reading, are ready
|
||||||
|
/// for writing, or have an exceptional condition pending, respectively.
|
||||||
|
/// Block until an event happens on the specified file descriptors.
|
||||||
|
/// @return true if socket has data ready, or false if not ready or timed out.
|
||||||
|
virtual bool Select(void) {
|
||||||
|
return Select(0, 0);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Examine the socket descriptor sets currently owned by the instance of
|
||||||
|
/// the socket class (the readfds, writefds, and errorfds parameters) to
|
||||||
|
/// see whether some of their descriptors are ready for reading, are ready
|
||||||
|
/// for writing, or have an exceptional condition pending, respectively.
|
||||||
|
/// @param nTimeoutSec timeout in seconds for select.
|
||||||
|
/// @param nTimeoutUSec timeout in micro seconds for select.
|
||||||
|
/// @return true if socket has data ready, or false if not ready or timed out.
|
||||||
|
virtual bool Select(int32_t nTimeoutSec, int32_t nTimeoutUSec);
|
||||||
|
|
||||||
|
|
||||||
|
virtual int WaitForData(size_t data_count, uint32_t timeout,
|
||||||
|
size_t *returned_size);
|
||||||
|
|
||||||
|
/// Does the current instance of the socket object contain a valid socket
|
||||||
|
/// descriptor.
|
||||||
|
/// @return true if the socket object contains a valid socket descriptor.
|
||||||
|
virtual bool IsSocketValid(void) {
|
||||||
|
return (m_socket != SocketError);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Provides a standard error code for cross platform development by
|
||||||
|
/// mapping the operating system error to an error defined by the CSocket
|
||||||
|
/// class.
|
||||||
|
void TranslateSocketError(void);
|
||||||
|
|
||||||
|
/// Returns a human-readable description of the given error code
|
||||||
|
/// or the last error code of a socket
|
||||||
|
static const char *DescribeError(CSocketError err);
|
||||||
|
///
|
||||||
|
/// \brief DescribeError
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual const char *DescribeError() {
|
||||||
|
return DescribeError(m_socketErrno);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Attempts to receive a block of data on an established connection.
|
||||||
|
/// @param nMaxBytes maximum number of bytes to receive.
|
||||||
|
/// @param pBuffer, memory where to receive the data,
|
||||||
|
/// NULL receives to internal buffer returned with GetData()
|
||||||
|
/// Non-NULL receives directly there, but GetData() will return WRONG ptr!
|
||||||
|
/// @return number of bytes actually received.
|
||||||
|
/// @return of zero means the connection has been shutdown on the other side.
|
||||||
|
/// @return of -1 means that an error has occurred.
|
||||||
|
virtual int32_t Receive(int32_t nMaxBytes = 1, uint8_t *pBuffer = 0);
|
||||||
|
|
||||||
|
/// Attempts to send a block of data on an established connection.
|
||||||
|
/// @param pBuf block of data to be sent.
|
||||||
|
/// @param bytesToSend size of data block to be sent.
|
||||||
|
/// @return number of bytes actually sent.
|
||||||
|
/// @return of zero means the connection has been shutdown on the other side.
|
||||||
|
/// @return of -1 means that an error has occurred.
|
||||||
|
virtual int32_t Send(const uint8_t *pBuf, size_t bytesToSend);
|
||||||
|
|
||||||
|
/// Attempts to send at most nNumItem blocks described by sendVector
|
||||||
|
/// to the socket descriptor associated with the socket object.
|
||||||
|
/// @param sendVector pointer to an array of iovec structures
|
||||||
|
/// @param nNumItems number of items in the vector to process
|
||||||
|
/// <br>\b NOTE: Buffers are processed in the order specified.
|
||||||
|
/// @return number of bytes actually sent, return of zero means the
|
||||||
|
/// connection has been shutdown on the other side, and a return of -1
|
||||||
|
/// means that an error has occurred.
|
||||||
|
virtual int32_t Send(const struct iovec *sendVector, int32_t nNumItems);
|
||||||
|
|
||||||
|
/// Copies data between one file descriptor and another.
|
||||||
|
/// On some systems this copying is done within the kernel, and thus is
|
||||||
|
/// more efficient than the combination of CSimpleSocket::Send and
|
||||||
|
/// CSimpleSocket::Receive, which would require transferring data to and
|
||||||
|
/// from user space.
|
||||||
|
/// <br>\b Note: This is available on all implementations, but the kernel
|
||||||
|
/// implementation is only available on Unix type systems.
|
||||||
|
/// @param nOutFd descriptor opened for writing.
|
||||||
|
/// @param nInFd descriptor opened for reading.
|
||||||
|
/// @param pOffset from which to start reading data from input file.
|
||||||
|
/// @param nCount number of bytes to copy between file descriptors.
|
||||||
|
/// @return number of bytes written to the out socket descriptor.
|
||||||
|
virtual int32_t SendFile(int32_t nOutFd, int32_t nInFd, off_t *pOffset,
|
||||||
|
int32_t nCount);
|
||||||
|
|
||||||
|
/// Returns blocking/non-blocking state of socket.
|
||||||
|
/// @return true if the socket is non-blocking, else return false.
|
||||||
|
bool IsNonblocking(void) {
|
||||||
|
return (m_bIsBlocking == false);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Set the socket to blocking.
|
||||||
|
/// @return true if successful set to blocking, else return false;
|
||||||
|
bool SetBlocking(void);
|
||||||
|
|
||||||
|
/// Set the socket as non-blocking.
|
||||||
|
/// @return true if successful set to non-blocking, else return false;
|
||||||
|
bool SetNonblocking(void);
|
||||||
|
|
||||||
|
/// Get a pointer to internal receive buffer. The user MUST not free this
|
||||||
|
/// pointer when finished. This memory is managed internally by the CSocket
|
||||||
|
/// class.
|
||||||
|
/// @return pointer to data if valid, else returns NULL.
|
||||||
|
uint8_t *GetData(void) {
|
||||||
|
return m_pBuffer;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Returns the number of bytes received on the last call to
|
||||||
|
/// CSocket::Receive().
|
||||||
|
/// @return number of bytes received.
|
||||||
|
int32_t GetBytesReceived(void) {
|
||||||
|
return m_nBytesReceived;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Returns the number of bytes sent on the last call to
|
||||||
|
/// CSocket::Send().
|
||||||
|
/// @return number of bytes sent.
|
||||||
|
int32_t GetBytesSent(void) {
|
||||||
|
return m_nBytesSent;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Controls the actions taken when CSimpleSocket::Close is executed on a
|
||||||
|
/// socket object that has unsent data. The default value for this option
|
||||||
|
/// is \b off.
|
||||||
|
/// - Following are the three possible scenarios.
|
||||||
|
/// -# \b bEnable is false, CSimpleSocket::Close returns immediately, but
|
||||||
|
/// any unset data is transmitted (after CSimpleSocket::Close returns)
|
||||||
|
/// -# \b bEnable is true and \b nTime is zero, CSimpleSocket::Close return
|
||||||
|
/// immediately and any unsent data is discarded.
|
||||||
|
/// -# \b bEnable is true and \b nTime is nonzero, CSimpleSocket::Close does
|
||||||
|
/// not return until all unsent data is transmitted (or the connection is
|
||||||
|
/// Closed by the remote system).
|
||||||
|
/// <br><p>
|
||||||
|
/// @param bEnable true to enable option false to disable option.
|
||||||
|
/// @param nTime time in seconds to linger.
|
||||||
|
/// @return true if option successfully set
|
||||||
|
bool SetOptionLinger(bool bEnable, uint16_t nTime);
|
||||||
|
|
||||||
|
/// Tells the kernel that even if this port is busy (in the TIME_WAIT state),
|
||||||
|
/// go ahead and reuse it anyway. If it is busy, but with another state,
|
||||||
|
/// you will still get an address already in use error.
|
||||||
|
/// @return true if option successfully set
|
||||||
|
bool SetOptionReuseAddr();
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of seconds a
|
||||||
|
/// call to CSimpleSocket::Open waits until it completes.
|
||||||
|
/// @return the length of time in seconds
|
||||||
|
int32_t GetConnectTimeoutSec(void) {
|
||||||
|
return m_stConnectTimeout.tv_sec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of microseconds
|
||||||
|
/// a call to CSimpleSocket::Open waits until it completes.
|
||||||
|
/// @return the length of time in microseconds
|
||||||
|
int32_t GetConnectTimeoutUSec(void) {
|
||||||
|
return m_stConnectTimeout.tv_usec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Sets the timeout value that specifies the maximum amount of time a call
|
||||||
|
/// to CSimpleSocket::Receive waits until it completes. Use the method
|
||||||
|
/// CSimpleSocket::SetReceiveTimeout to specify the number of seconds to wait.
|
||||||
|
/// If a call to CSimpleSocket::Receive has blocked for the specified length of
|
||||||
|
/// time without receiving additional data, it returns with a partial count
|
||||||
|
/// or CSimpleSocket::GetSocketError set to CSimpleSocket::SocketEwouldblock if no data
|
||||||
|
/// were received.
|
||||||
|
/// @param nConnectTimeoutSec of timeout in seconds.
|
||||||
|
/// @param nConnectTimeoutUsec of timeout in microseconds.
|
||||||
|
/// @return true if socket connection timeout was successfully set.
|
||||||
|
void SetConnectTimeout(int32_t nConnectTimeoutSec,
|
||||||
|
int32_t nConnectTimeoutUsec = 0) {
|
||||||
|
m_stConnectTimeout.tv_sec = nConnectTimeoutSec;
|
||||||
|
m_stConnectTimeout.tv_usec = nConnectTimeoutUsec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of seconds a
|
||||||
|
/// a call to CSimpleSocket::Receive waits until it completes.
|
||||||
|
/// @return the length of time in seconds
|
||||||
|
int32_t GetReceiveTimeoutSec(void) {
|
||||||
|
return m_stRecvTimeout.tv_sec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of microseconds
|
||||||
|
/// a call to CSimpleSocket::Receive waits until it completes.
|
||||||
|
/// @return the length of time in microseconds
|
||||||
|
int32_t GetReceiveTimeoutUSec(void) {
|
||||||
|
return m_stRecvTimeout.tv_usec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Sets the timeout value that specifies the maximum amount of time a call
|
||||||
|
/// to CSimpleSocket::Receive waits until it completes. Use the method
|
||||||
|
/// CSimpleSocket::SetReceiveTimeout to specify the number of seconds to wait.
|
||||||
|
/// If a call to CSimpleSocket::Receive has blocked for the specified length of
|
||||||
|
/// time without receiving additional data, it returns with a partial count
|
||||||
|
/// or CSimpleSocket::GetSocketError set to CSimpleSocket::SocketEwouldblock if no data
|
||||||
|
/// were received.
|
||||||
|
/// @param nRecvTimeoutSec of timeout in seconds.
|
||||||
|
/// @param nRecvTimeoutUsec of timeout in microseconds.
|
||||||
|
/// @return true if socket timeout was successfully set.
|
||||||
|
bool SetReceiveTimeout(int32_t nRecvTimeoutSec, int32_t nRecvTimeoutUsec = 0);
|
||||||
|
|
||||||
|
/// Enable/disable multicast for a socket. This options is only valid for
|
||||||
|
/// socket descriptors of type CSimpleSocket::SocketTypeUdp.
|
||||||
|
/// @return true if multicast was enabled or false if socket type is not
|
||||||
|
/// CSimpleSocket::SocketTypeUdp and the error will be set to
|
||||||
|
/// CSimpleSocket::SocketProtocolError
|
||||||
|
bool SetMulticast(bool bEnable, uint8_t multicastTTL = 1);
|
||||||
|
|
||||||
|
/// Return true if socket is multicast or false is socket is unicast
|
||||||
|
/// @return true if multicast is enabled
|
||||||
|
bool GetMulticast() {
|
||||||
|
return m_bIsMulticast;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Bind socket to a specific interface when using multicast.
|
||||||
|
/// @return true if successfully bound to interface
|
||||||
|
bool BindInterface(const char *pInterface);
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of seconds a
|
||||||
|
/// a call to CSimpleSocket::Send waits until it completes.
|
||||||
|
/// @return the length of time in seconds
|
||||||
|
int32_t GetSendTimeoutSec(void) {
|
||||||
|
return m_stSendTimeout.tv_sec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum number of microseconds
|
||||||
|
/// a call to CSimpleSocket::Send waits until it completes.
|
||||||
|
/// @return the length of time in microseconds
|
||||||
|
int32_t GetSendTimeoutUSec(void) {
|
||||||
|
return m_stSendTimeout.tv_usec;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Gets the timeout value that specifies the maximum amount of time a call
|
||||||
|
/// to CSimpleSocket::Send waits until it completes.
|
||||||
|
/// @return the length of time in seconds
|
||||||
|
bool SetSendTimeout(int32_t nSendTimeoutSec, int32_t nSendTimeoutUsec = 0);
|
||||||
|
|
||||||
|
/// Returns the last error that occured for the instace of the CSimpleSocket
|
||||||
|
/// instance. This method should be called immediately to retrieve the
|
||||||
|
/// error code for the failing mehtod call.
|
||||||
|
/// @return last error that occured.
|
||||||
|
CSocketError GetSocketError(void) {
|
||||||
|
return m_socketErrno;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Get the total time the of the last operation in milliseconds.
|
||||||
|
/// @return number of milliseconds of last operation.
|
||||||
|
uint32_t GetTotalTimeMs() {
|
||||||
|
return m_timer.GetMilliSeconds();
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Get the total time the of the last operation in microseconds.
|
||||||
|
/// @return number of microseconds or last operation.
|
||||||
|
uint64_t GetTotalTimeUsec() {
|
||||||
|
return m_timer.GetMicroSeconds();
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Return Differentiated Services Code Point (DSCP) value currently set on the socket object.
|
||||||
|
/// @return DSCP for current socket object.
|
||||||
|
/// <br><br> \b NOTE: Windows special notes http://support.microsoft.com/kb/248611.
|
||||||
|
int GetSocketDscp(void);
|
||||||
|
|
||||||
|
/// Set Differentiated Services Code Point (DSCP) for socket object.
|
||||||
|
/// @param nDscp value of TOS setting which will be converted to DSCP
|
||||||
|
/// @return true if DSCP value was properly set
|
||||||
|
/// <br><br> \b NOTE: Windows special notes http://support.microsoft.com/kb/248611.
|
||||||
|
bool SetSocketDscp(int nDscp);
|
||||||
|
|
||||||
|
/// Return socket descriptor
|
||||||
|
/// @return socket descriptor which is a signed 32 bit integer.
|
||||||
|
SOCKET GetSocketDescriptor() {
|
||||||
|
return m_socket;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Return socket descriptor
|
||||||
|
/// @return socket descriptor which is a signed 32 bit integer.
|
||||||
|
CSocketType GetSocketType() {
|
||||||
|
return m_nSocketType;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// set socket descriptor
|
||||||
|
void SetSocketType(const CSocketType &type) {
|
||||||
|
m_nSocketType = type;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Returns clients Internet host address as a string in standard numbers-and-dots notation.
|
||||||
|
/// @return NULL if invalid
|
||||||
|
const char *GetClientAddr() {
|
||||||
|
return inet_ntoa(m_stClientSockaddr.sin_addr);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Returns the port number on which the client is connected.
|
||||||
|
/// @return client port number.
|
||||||
|
uint16_t GetClientPort() {
|
||||||
|
return m_stClientSockaddr.sin_port;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Returns server Internet host address as a string in standard numbers-and-dots notation.
|
||||||
|
/// @return NULL if invalid
|
||||||
|
const char *GetServerAddr() {
|
||||||
|
return inet_ntoa(m_stServerSockaddr.sin_addr);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Returns the port number on which the server is connected.
|
||||||
|
/// @return server port number.
|
||||||
|
uint16_t GetServerPort() {
|
||||||
|
return ntohs(m_stServerSockaddr.sin_port);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Get the TCP receive buffer window size for the current socket object.
|
||||||
|
/// <br><br>\b NOTE: Linux will set the receive buffer to twice the value passed.
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP receive buffer window size if successful.
|
||||||
|
uint32_t GetReceiveWindowSize() {
|
||||||
|
return GetWindowSize(SO_RCVBUF);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Get the TCP send buffer window size for the current socket object.
|
||||||
|
/// <br><br>\b NOTE: Linux will set the send buffer to twice the value passed.
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP receive buffer window size if successful.
|
||||||
|
uint32_t GetSendWindowSize() {
|
||||||
|
return GetWindowSize(SO_SNDBUF);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Set the TCP receive buffer window size for the current socket object.
|
||||||
|
/// <br><br>\b NOTE: Linux will set the receive buffer to twice the value passed.
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP send buffer window size if successful.
|
||||||
|
uint32_t SetReceiveWindowSize(uint32_t nWindowSize) {
|
||||||
|
return SetWindowSize(SO_RCVBUF, nWindowSize);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Set the TCP send buffer window size for the current socket object.
|
||||||
|
/// <br><br>\b NOTE: Linux will set the send buffer to twice the value passed.
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP send buffer window size if successful.
|
||||||
|
uint32_t SetSendWindowSize(uint32_t nWindowSize) {
|
||||||
|
return SetWindowSize(SO_SNDBUF, nWindowSize);
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Disable the Nagle algorithm (Set TCP_NODELAY to true)
|
||||||
|
/// @return false if failed to set socket option otherwise return true;
|
||||||
|
bool DisableNagleAlgoritm();
|
||||||
|
|
||||||
|
/// Enable the Nagle algorithm (Set TCP_NODELAY to false)
|
||||||
|
/// @return false if failed to set socket option otherwise return true;
|
||||||
|
bool EnableNagleAlgoritm();
|
||||||
|
|
||||||
|
virtual bool Open(const char *pAddr, uint16_t nPort) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief bindport
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual bool bindport(const char *, uint32_t);
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief open
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual bool open();
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief isOpen
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual bool isOpen();
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief closePort
|
||||||
|
///
|
||||||
|
virtual void closePort();
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief flush
|
||||||
|
///
|
||||||
|
virtual void flush();
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief available
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual size_t available();
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief readSize
|
||||||
|
/// \param size
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual std::string readSize(size_t size = 1);
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief waitfordata
|
||||||
|
/// \param data_count
|
||||||
|
/// \param timeout
|
||||||
|
/// \param returned_size
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual int waitfordata(size_t data_count, uint32_t timeout = -1,
|
||||||
|
size_t *returned_size = NULL);
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief writeData
|
||||||
|
/// \param data
|
||||||
|
/// \param size
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual size_t writeData(const uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief readData
|
||||||
|
/// \param data
|
||||||
|
/// \param size
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual size_t readData(uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
|
||||||
|
protected:
|
||||||
|
/// Set internal socket error to that specified error
|
||||||
|
/// @param error type of error
|
||||||
|
void SetSocketError(CSimpleSocket::CSocketError error) {
|
||||||
|
m_socketErrno = error;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Set object socket handle to that specified as parameter
|
||||||
|
/// @param socket value of socket descriptor
|
||||||
|
void SetSocketHandle(SOCKET socket) {
|
||||||
|
m_socket = socket;
|
||||||
|
};
|
||||||
|
|
||||||
|
/// Flush the socket descriptor owned by the object.
|
||||||
|
/// @return true data was successfully sent, else return false;
|
||||||
|
bool Flush();
|
||||||
|
|
||||||
|
private:
|
||||||
|
/// Generic function used to get the send/receive window size
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP window size if successful.
|
||||||
|
uint32_t GetWindowSize(uint32_t nOptionName);
|
||||||
|
|
||||||
|
/// Generic function used to set the send/receive window size
|
||||||
|
/// @return zero on failure else the number of bytes of the TCP window size if successful.
|
||||||
|
uint32_t SetWindowSize(uint32_t nOptionName, uint32_t nWindowSize);
|
||||||
|
|
||||||
|
|
||||||
|
/// Attempts to send at most nNumItem blocks described by sendVector
|
||||||
|
/// to the socket descriptor associated with the socket object.
|
||||||
|
/// @param sendVector pointer to an array of iovec structures
|
||||||
|
/// @param nNumItems number of items in the vector to process
|
||||||
|
/// <br>\b Note: This implementation is for systems that don't natively
|
||||||
|
/// support this functionality.
|
||||||
|
/// @return number of bytes actually sent, return of zero means the
|
||||||
|
/// connection has been shutdown on the other side, and a return of -1
|
||||||
|
/// means that an error has occurred.
|
||||||
|
int32_t Writev(const struct iovec *pVector, size_t nCount);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
CSimpleSocket *operator=(CSimpleSocket &socket);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
SOCKET m_socket; /// socket handle
|
||||||
|
CSocketError m_socketErrno; /// number of last error
|
||||||
|
uint8_t *m_pBuffer; /// internal send/receive buffer
|
||||||
|
int32_t
|
||||||
|
m_nBufferSize; /// size of internal send/receive buffer
|
||||||
|
int32_t m_nSocketDomain; /// socket type PF_INET, PF_INET6
|
||||||
|
CSocketType m_nSocketType; /// socket type - UDP, TCP or RAW
|
||||||
|
int32_t m_nBytesReceived; /// number of bytes received
|
||||||
|
int32_t m_nBytesSent; /// number of bytes sent
|
||||||
|
uint32_t m_nFlags; /// socket flags
|
||||||
|
bool m_bIsBlocking; /// is socket blocking
|
||||||
|
bool m_bIsMulticast; /// is the UDP socket multicast;
|
||||||
|
struct timeval m_stConnectTimeout; /// connection timeout
|
||||||
|
struct timeval m_stRecvTimeout; /// receive timeout
|
||||||
|
struct timeval m_stSendTimeout; /// send timeout
|
||||||
|
struct sockaddr_in m_stServerSockaddr; /// server address
|
||||||
|
struct sockaddr_in m_stClientSockaddr; /// client address
|
||||||
|
struct sockaddr_in m_stMulticastGroup; /// multicast group to bind to
|
||||||
|
struct linger m_stLinger; /// linger flag
|
||||||
|
CStatTimer m_timer; /// internal statistics.
|
||||||
|
#if defined(_WIN32)
|
||||||
|
WSADATA m_hWSAData; /// Windows
|
||||||
|
#endif
|
||||||
|
fd_set m_writeFds; /// write file descriptor set
|
||||||
|
fd_set m_readFds; /// read file descriptor set
|
||||||
|
fd_set m_errorFds; /// error file descriptor set
|
||||||
|
|
||||||
|
std::string m_addr;
|
||||||
|
uint32_t m_port;
|
||||||
|
bool m_open;
|
||||||
|
};
|
||||||
|
|
||||||
|
}//namespace socket
|
||||||
|
}//namespace core
|
||||||
|
}//namespace ydlidar
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* __SOCKET_H__ */
|
||||||
|
|
|
@ -0,0 +1,150 @@
|
||||||
|
/*----------------------------------------------------------------------------*/
|
||||||
|
/* */
|
||||||
|
/* StatTimer.h: interface for the CStatTimer class. */
|
||||||
|
/* */
|
||||||
|
/* Author: Mark Carrier (mark@carrierlabs.com) */
|
||||||
|
/* */
|
||||||
|
/*----------------------------------------------------------------------------*/
|
||||||
|
/* Copyright (c) 2006 CarrierLabs, LLC. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
*
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
*
|
||||||
|
* 3. The name of the author may not be used to endorse or promote products
|
||||||
|
* derived from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* 4. The name "CarrierLabs" must not be used to
|
||||||
|
* endorse or promote products derived from this software without
|
||||||
|
* prior written permission. For written permission, please contact
|
||||||
|
* mark@carrierlabs.com.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY MARK CARRIER ``AS IS'' AND ANY
|
||||||
|
* EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||||
|
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL MARK CARRIER OR
|
||||||
|
* ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
||||||
|
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
|
||||||
|
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
|
||||||
|
* OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#ifndef __CSTATTIMER_H__
|
||||||
|
#define __CSTATTIMER_H__
|
||||||
|
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include <Winsock2.h>
|
||||||
|
#include <time.h>
|
||||||
|
#else
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#if !defined (_WINSOCK2API_) && !defined(_WINSOCKAPI_)
|
||||||
|
struct timeval {
|
||||||
|
long tv_sec; /* seconds */
|
||||||
|
long tv_usec; /* and microseconds */
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
inline static int gettimeofday(struct timeval *tv, void *tz) {
|
||||||
|
union {
|
||||||
|
long long ns100;
|
||||||
|
FILETIME t;
|
||||||
|
} now;
|
||||||
|
GetSystemTimeAsFileTime(&now.t);
|
||||||
|
tv->tv_usec = long((now.ns100 / 10LL) % 1000000LL);
|
||||||
|
tv->tv_sec = long((now.ns100 - 116444736000000000LL) / 10000000LL);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#undef HAS_CLOCK_GETTIME
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#define GET_CLOCK_COUNT(x) gettimeofday(x, NULL)
|
||||||
|
|
||||||
|
#include <core/base/v8stdint.h>
|
||||||
|
|
||||||
|
|
||||||
|
/// Class to abstract socket communications in a cross platform manner.
|
||||||
|
/// This class is designed
|
||||||
|
class CStatTimer {
|
||||||
|
public:
|
||||||
|
CStatTimer() {
|
||||||
|
memset(&m_startTime, 0, sizeof(struct timeval));
|
||||||
|
memset(&m_endTime, 0, sizeof(struct timeval));
|
||||||
|
};
|
||||||
|
|
||||||
|
~CStatTimer() {
|
||||||
|
};
|
||||||
|
|
||||||
|
void Initialize() {
|
||||||
|
memset(&m_startTime, 0, sizeof(struct timeval));
|
||||||
|
memset(&m_endTime, 0, sizeof(struct timeval));
|
||||||
|
};
|
||||||
|
|
||||||
|
struct timeval GetStartTime() {
|
||||||
|
return m_startTime;
|
||||||
|
};
|
||||||
|
void SetStartTime() {
|
||||||
|
GET_CLOCK_COUNT(&m_startTime);
|
||||||
|
};
|
||||||
|
|
||||||
|
struct timeval GetEndTime() {
|
||||||
|
return m_endTime;
|
||||||
|
};
|
||||||
|
void SetEndTime() {
|
||||||
|
GET_CLOCK_COUNT(&m_endTime);
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t GetMilliSeconds() {
|
||||||
|
return (CalcTotalUSec() / MILLISECONDS_CONVERSION);
|
||||||
|
};
|
||||||
|
uint64_t GetMicroSeconds() {
|
||||||
|
return (CalcTotalUSec());
|
||||||
|
};
|
||||||
|
uint32_t GetSeconds() {
|
||||||
|
return (CalcTotalUSec() / MICROSECONDS_CONVERSION);
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint64_t GetCurrentTime() {
|
||||||
|
#if HAS_CLOCK_GETTIME
|
||||||
|
struct timespec tim;
|
||||||
|
clock_gettime(CLOCK_REALTIME, &tim);
|
||||||
|
return (uint64_t)(tim.tv_sec * 1000000000LL + tim.tv_nsec);
|
||||||
|
#else
|
||||||
|
struct timeval timeofday;
|
||||||
|
gettimeofday(&timeofday, NULL);
|
||||||
|
return (uint64_t)(timeofday.tv_sec * 1000000000LL + timeofday.tv_usec * 1000);
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
private:
|
||||||
|
uint32_t CalcTotalUSec() {
|
||||||
|
return (((m_endTime.tv_sec - m_startTime.tv_sec) * MICROSECONDS_CONVERSION) +
|
||||||
|
(m_endTime.tv_usec - m_startTime.tv_usec));
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
struct timeval m_startTime;
|
||||||
|
struct timeval m_endTime;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // __CSTATTIMER_H__
|
|
@ -0,0 +1,10 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_src_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
||||||
|
subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
foreach(subdir ${SUBDIRS})
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/${subdir} )
|
||||||
|
add_subdirectory(${subdir})
|
||||||
|
endforeach()
|
|
@ -0,0 +1,48 @@
|
||||||
|
/*********************************************************************
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2018, EAIBOT, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of the Willow Garage nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*********************************************************************/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include "impl\windows\win.h"
|
||||||
|
#include "impl\windows\win_serial.h"
|
||||||
|
#elif defined(__GNUC__)
|
||||||
|
#include "impl/unix/unix.h"
|
||||||
|
#include "impl/unix/unix_serial.h"
|
||||||
|
#else
|
||||||
|
#error "unsupported target"
|
||||||
|
#endif
|
||||||
|
#include <core/base/thread.h>
|
||||||
|
#include <core/base/locker.h>
|
||||||
|
#include <core/base/timer.h>
|
||||||
|
|
|
@ -0,0 +1,8 @@
|
||||||
|
IF (WIN32)
|
||||||
|
add_subdirectory(windows)
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/windows)
|
||||||
|
ELSE()
|
||||||
|
add_subdirectory(unix)
|
||||||
|
include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/unix)
|
||||||
|
ENDIF()
|
||||||
|
|
|
@ -0,0 +1,4 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_src_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
|
@ -0,0 +1,332 @@
|
||||||
|
#if defined(__linux__)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Copyright (c) 2014 Craig Lilley <cralilley@gmail.com>
|
||||||
|
* This software is made available under the terms of the MIT licence.
|
||||||
|
* A copy of the licence can be obtained from:
|
||||||
|
* http://opensource.org/licenses/MIT
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <sstream>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <iostream>
|
||||||
|
#include <fstream>
|
||||||
|
#include <cstdio>
|
||||||
|
#include <cstdarg>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
#include <glob.h>
|
||||||
|
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <core/serial/serial.h>
|
||||||
|
using namespace ydlidar::core;
|
||||||
|
using ydlidar::core::serial::PortInfo;
|
||||||
|
using std::istringstream;
|
||||||
|
using std::ifstream;
|
||||||
|
using std::getline;
|
||||||
|
using std::vector;
|
||||||
|
using std::string;
|
||||||
|
using std::cout;
|
||||||
|
using std::endl;
|
||||||
|
|
||||||
|
static vector<string> glob(const vector<string> &patterns);
|
||||||
|
static string basename(const string &path);
|
||||||
|
static string dirname(const string &path);
|
||||||
|
static bool path_exists(const string &path);
|
||||||
|
static string realpath(const string &path);
|
||||||
|
static string usb_sysfs_friendly_name(const string &sys_usb_path,
|
||||||
|
string &device_id);
|
||||||
|
static vector<string> get_sysfs_info(const string &device_path);
|
||||||
|
static string read_line(const string &file);
|
||||||
|
static string usb_sysfs_hw_string(const string &sysfs_path);
|
||||||
|
static string format(const char *format, ...);
|
||||||
|
|
||||||
|
vector<string>
|
||||||
|
glob(const vector<string> &patterns) {
|
||||||
|
vector<string> paths_found;
|
||||||
|
|
||||||
|
if (patterns.size() == 0) {
|
||||||
|
return paths_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
glob_t glob_results;
|
||||||
|
|
||||||
|
int glob_retval = glob(patterns[0].c_str(), 0, NULL, &glob_results);
|
||||||
|
|
||||||
|
vector<string>::const_iterator iter = patterns.begin();
|
||||||
|
|
||||||
|
while (++iter != patterns.end()) {
|
||||||
|
glob_retval = glob(iter->c_str(), GLOB_APPEND, NULL, &glob_results);
|
||||||
|
}
|
||||||
|
|
||||||
|
for (size_t path_index = 0; path_index < glob_results.gl_pathc; path_index++) {
|
||||||
|
paths_found.push_back(glob_results.gl_pathv[path_index]);
|
||||||
|
}
|
||||||
|
|
||||||
|
globfree(&glob_results);
|
||||||
|
|
||||||
|
return paths_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
basename(const string &path) {
|
||||||
|
size_t pos = path.rfind("/");
|
||||||
|
|
||||||
|
if (pos == std::string::npos) {
|
||||||
|
return path;
|
||||||
|
}
|
||||||
|
|
||||||
|
return string(path, pos + 1, string::npos);
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
dirname(const string &path) {
|
||||||
|
size_t pos = path.rfind("/");
|
||||||
|
|
||||||
|
if (pos == std::string::npos) {
|
||||||
|
return path;
|
||||||
|
} else if (pos == 0) {
|
||||||
|
return "/";
|
||||||
|
}
|
||||||
|
|
||||||
|
return string(path, 0, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
path_exists(const string &path) {
|
||||||
|
struct stat sb;
|
||||||
|
|
||||||
|
if (stat(path.c_str(), &sb) == 0) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
realpath(const string &path) {
|
||||||
|
char *real_path = realpath(path.c_str(), NULL);
|
||||||
|
|
||||||
|
string result;
|
||||||
|
|
||||||
|
if (real_path != NULL) {
|
||||||
|
result = real_path;
|
||||||
|
|
||||||
|
free(real_path);
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
usb_sysfs_friendly_name(const string &sys_usb_path, string &device_id) {
|
||||||
|
unsigned int device_number = 0;
|
||||||
|
|
||||||
|
istringstream(read_line(sys_usb_path + "/devnum")) >> device_number;
|
||||||
|
|
||||||
|
string manufacturer = read_line(sys_usb_path + "/manufacturer");
|
||||||
|
|
||||||
|
string product = read_line(sys_usb_path + "/product");
|
||||||
|
|
||||||
|
string serial = read_line(sys_usb_path + "/serial");
|
||||||
|
|
||||||
|
device_id = read_line(sys_usb_path + "/devpath");
|
||||||
|
|
||||||
|
if (manufacturer.empty() && product.empty() && serial.empty()) {
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
|
||||||
|
return format("%s %s %s", manufacturer.c_str(), product.c_str(),
|
||||||
|
serial.c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string>
|
||||||
|
get_sysfs_info(const string &device_path) {
|
||||||
|
string device_name = basename(device_path);
|
||||||
|
|
||||||
|
string friendly_name;
|
||||||
|
|
||||||
|
string hardware_id;
|
||||||
|
|
||||||
|
string device_id;
|
||||||
|
|
||||||
|
string sys_device_path = format("/sys/class/tty/%s/device",
|
||||||
|
device_name.c_str());
|
||||||
|
|
||||||
|
if (device_name.compare(0, 6, "ttyUSB") == 0) {
|
||||||
|
sys_device_path = dirname(dirname(realpath(sys_device_path)));
|
||||||
|
|
||||||
|
if (path_exists(sys_device_path)) {
|
||||||
|
friendly_name = usb_sysfs_friendly_name(sys_device_path, device_id);
|
||||||
|
|
||||||
|
hardware_id = usb_sysfs_hw_string(sys_device_path);
|
||||||
|
}
|
||||||
|
} else if (device_name.compare(0, 6, "ttyACM") == 0) {
|
||||||
|
sys_device_path = dirname(realpath(sys_device_path));
|
||||||
|
|
||||||
|
if (path_exists(sys_device_path)) {
|
||||||
|
friendly_name = usb_sysfs_friendly_name(sys_device_path, device_id);
|
||||||
|
|
||||||
|
hardware_id = usb_sysfs_hw_string(sys_device_path);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// Try to read ID string of PCI device
|
||||||
|
|
||||||
|
string sys_id_path = sys_device_path + "/id";
|
||||||
|
|
||||||
|
if (path_exists(sys_id_path)) {
|
||||||
|
hardware_id = read_line(sys_id_path);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (friendly_name.empty()) {
|
||||||
|
friendly_name = device_name;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hardware_id.empty()) {
|
||||||
|
hardware_id = "n/a";
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string> result;
|
||||||
|
result.push_back(friendly_name);
|
||||||
|
result.push_back(hardware_id);
|
||||||
|
result.push_back(device_id);
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
read_line(const string &file) {
|
||||||
|
ifstream ifs(file.c_str(), ifstream::in);
|
||||||
|
|
||||||
|
string line;
|
||||||
|
|
||||||
|
if (ifs) {
|
||||||
|
getline(ifs, line);
|
||||||
|
}
|
||||||
|
|
||||||
|
return line;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
format(const char *format, ...) {
|
||||||
|
va_list ap;
|
||||||
|
|
||||||
|
size_t buffer_size_bytes = 256;
|
||||||
|
|
||||||
|
string result;
|
||||||
|
|
||||||
|
char *buffer = (char *)malloc(buffer_size_bytes);
|
||||||
|
|
||||||
|
if (buffer == NULL) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool done = false;
|
||||||
|
|
||||||
|
unsigned int loop_count = 0;
|
||||||
|
|
||||||
|
while (!done) {
|
||||||
|
va_start(ap, format);
|
||||||
|
|
||||||
|
int return_value = vsnprintf(buffer, buffer_size_bytes, format, ap);
|
||||||
|
|
||||||
|
if (return_value < 0) {
|
||||||
|
done = true;
|
||||||
|
} else if (return_value >= (int)buffer_size_bytes) {
|
||||||
|
// Realloc and try again.
|
||||||
|
|
||||||
|
buffer_size_bytes = return_value + 1;
|
||||||
|
|
||||||
|
char *new_buffer_ptr = (char *)realloc(buffer, buffer_size_bytes);
|
||||||
|
|
||||||
|
if (new_buffer_ptr == NULL) {
|
||||||
|
done = true;
|
||||||
|
} else {
|
||||||
|
buffer = new_buffer_ptr;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
result = buffer;
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
va_end(ap);
|
||||||
|
|
||||||
|
if (++loop_count > 5) {
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
free(buffer);
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
usb_sysfs_hw_string(const string &sysfs_path) {
|
||||||
|
string serial_number = read_line(sysfs_path + "/serial");
|
||||||
|
|
||||||
|
if (serial_number.length() > 0) {
|
||||||
|
serial_number = format("SNR=%s", serial_number.c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
string vid = read_line(sysfs_path + "/idVendor");
|
||||||
|
|
||||||
|
string pid = read_line(sysfs_path + "/idProduct");
|
||||||
|
|
||||||
|
return format("USB VID:PID=%s:%s %s", vid.c_str(), pid.c_str(),
|
||||||
|
serial_number.c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<PortInfo>
|
||||||
|
serial::list_ports() {
|
||||||
|
vector<PortInfo> results;
|
||||||
|
|
||||||
|
vector<string> search_globs;
|
||||||
|
search_globs.push_back("/dev/ttyACM*");
|
||||||
|
search_globs.push_back("/dev/ttyS*");
|
||||||
|
search_globs.push_back("/dev/ttyUSB*");
|
||||||
|
search_globs.push_back("/dev/tty.*");
|
||||||
|
search_globs.push_back("/dev/cu.*");
|
||||||
|
|
||||||
|
vector<string> devices_found = glob(search_globs);
|
||||||
|
|
||||||
|
vector<string>::iterator iter = devices_found.begin();
|
||||||
|
|
||||||
|
while (iter != devices_found.end()) {
|
||||||
|
string device = *iter++;
|
||||||
|
|
||||||
|
vector<string> sysfs_info = get_sysfs_info(device);
|
||||||
|
|
||||||
|
string friendly_name = sysfs_info[0];
|
||||||
|
|
||||||
|
string hardware_id = sysfs_info[1];
|
||||||
|
|
||||||
|
string device_id = sysfs_info[2];
|
||||||
|
|
||||||
|
std::size_t found = hardware_id.find("10c4:ea60");
|
||||||
|
std::size_t found1 = hardware_id.find("0483:5740");
|
||||||
|
|
||||||
|
|
||||||
|
if (found != std::string::npos || found1 != std::string::npos) {
|
||||||
|
PortInfo device_entry;
|
||||||
|
device_entry.port = device;
|
||||||
|
device_entry.description = friendly_name;
|
||||||
|
device_entry.hardware_id = hardware_id;
|
||||||
|
device_entry.device_id = device_id;
|
||||||
|
results.push_back(device_entry);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // defined(__linux__)
|
|
@ -0,0 +1,796 @@
|
||||||
|
/*
|
||||||
|
* lock.c
|
||||||
|
*
|
||||||
|
* Created on: 28 Mar 2018
|
||||||
|
* Author: Tony
|
||||||
|
* E-Mail: Tony@gmail.com
|
||||||
|
*/
|
||||||
|
#include "lock.h"
|
||||||
|
|
||||||
|
#ifndef WIN32
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <termios.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <sys/sysmacros.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <limits.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <signal.h>
|
||||||
|
#ifdef LFS
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
lfs_lock
|
||||||
|
accept: The name of the device to try to lock
|
||||||
|
perform: Create a lock file if there is not one already using a
|
||||||
|
lock file server.
|
||||||
|
return: 1 on failure 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int lfs_lock(const char *filename, int pid) {
|
||||||
|
int s;
|
||||||
|
int ret;
|
||||||
|
int size = 1024;
|
||||||
|
char *buffer = malloc(size);
|
||||||
|
struct sockaddr_in addr;
|
||||||
|
|
||||||
|
if (!(s = socket(AF_INET, SOCK_STREAM, 0)) > 0) {
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
addr.sin_family = AF_INET;
|
||||||
|
addr.sin_port = htons(50001);
|
||||||
|
addr.sin_addr.s_addr = inet_addr("127.0.0.1");
|
||||||
|
|
||||||
|
if (!connect(s, (struct sockaddr *) &addr, sizeof(addr)) == 0) {
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = recv(s, buffer, size, 0);
|
||||||
|
sprintf(buffer, "lock %s %i\n", filename, pid);
|
||||||
|
/* printf( "%s", buffer ); */
|
||||||
|
send(s, buffer, strlen(buffer), 0);
|
||||||
|
ret = recv(s, buffer, size, 0);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
buffer[ret] = '\0';
|
||||||
|
/* printf( "Message recieved: %s", buffer ); */
|
||||||
|
}
|
||||||
|
|
||||||
|
send(s, "quit\n", strlen("quit\n"), 0);
|
||||||
|
close(s);
|
||||||
|
|
||||||
|
/* printf("%s\n", buffer); */
|
||||||
|
if (buffer[0] == '2') {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
lfs_unlock
|
||||||
|
accept: The name of the device to try to unlock
|
||||||
|
perform: Remove a lock file if there is one using a
|
||||||
|
lock file server.
|
||||||
|
return: 1 on failure 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int lfs_unlock(const char *filename, int pid) {
|
||||||
|
int s;
|
||||||
|
int ret;
|
||||||
|
int size = 1024;
|
||||||
|
char *buffer = malloc(size);
|
||||||
|
struct sockaddr_in addr;
|
||||||
|
|
||||||
|
if (!(s = socket(AF_INET, SOCK_STREAM, 0)) > 0) {
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
addr.sin_family = AF_INET;
|
||||||
|
addr.sin_port = htons(50001);
|
||||||
|
addr.sin_addr.s_addr = inet_addr("127.0.0.1");
|
||||||
|
|
||||||
|
if (!connect(s, (struct sockaddr *) &addr, sizeof(addr)) == 0) {
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(buffer, "unlock %s %i\n", filename, pid);
|
||||||
|
/* printf( "%s", buffer ); */
|
||||||
|
send(s, buffer, strlen(buffer), 0);
|
||||||
|
ret = recv(s, buffer, size, 0);
|
||||||
|
|
||||||
|
if (ret > 0) {
|
||||||
|
buffer[ret] = '\0';
|
||||||
|
/* printf( "Message recieved: %s", buffer ); */
|
||||||
|
}
|
||||||
|
|
||||||
|
send(s, "quit\n", strlen("quit\n"), 0);
|
||||||
|
close(s);
|
||||||
|
|
||||||
|
if (buffer[0] == '2') {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
free(buffer);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
#endif /* LFS */
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
lib_lock_dev_unlock
|
||||||
|
accept: The name of the device to try to unlock
|
||||||
|
perform: Remove a lock file if there is one using a
|
||||||
|
lock file server.
|
||||||
|
return: 1 on failure 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments: This is for use with liblockdev which comes with Linux
|
||||||
|
distros. I suspect it will be problematic with embeded
|
||||||
|
Linux. taj
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
#ifdef LIBLOCKDEV
|
||||||
|
int lib_lock_dev_unlock(const char *filename, int pid) {
|
||||||
|
if (dev_unlock(filename, pid)) {
|
||||||
|
//report("fhs_unlock: Unable to remove LockFile\n");
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return (0);
|
||||||
|
}
|
||||||
|
#endif /* LIBLOCKDEV */
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
lib_lock_dev_lock
|
||||||
|
accept: The name of the device to try to lock
|
||||||
|
termios struct
|
||||||
|
perform: Create a lock file if there is not one already.
|
||||||
|
return: 1 on failure 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments: This is for use with liblockdev which comes with Linux
|
||||||
|
distros. I suspect it will be problematic with embeded
|
||||||
|
Linux. taj
|
||||||
|
One could load the library here rather than link it and
|
||||||
|
always try to use this.
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
#ifdef LIBLOCKDEV
|
||||||
|
int lib_lock_dev_lock(const char *filename, int pid) {
|
||||||
|
char message[80];
|
||||||
|
printf("LOCKING %s\n", filename);
|
||||||
|
|
||||||
|
if (dev_testlock(filename)) {
|
||||||
|
//report( "fhs_lock() lockstatus fail\n" );
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (dev_lock(filename)) {
|
||||||
|
sprintf(message,
|
||||||
|
"RXTX fhs_lock() Error: creating lock file for: %s: %s\n",
|
||||||
|
filename, strerror(errno));
|
||||||
|
// report_error( message );
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return (0);
|
||||||
|
}
|
||||||
|
#endif /* LIBLOCKDEV */
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
fhs_lock
|
||||||
|
accept: The name of the device to try to lock
|
||||||
|
termios struct
|
||||||
|
perform: Create a lock file if there is not one already.
|
||||||
|
return: 1 on failure 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments: This is for linux and freebsd only currently. I see SVR4 does
|
||||||
|
this differently and there are other proposed changes to the
|
||||||
|
Filesystem Hierachy Standard
|
||||||
|
more reading:
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int fhs_lock(const char *filename, int pid) {
|
||||||
|
/*
|
||||||
|
* There is a zoo of lockdir possibilities
|
||||||
|
* Its possible to check for stale processes with most of them.
|
||||||
|
* for now we will just check for the lockfile on most
|
||||||
|
* Problem lockfiles will be dealt with. Some may not even be in use.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
int fd, j;
|
||||||
|
char lockinfo[12];
|
||||||
|
char file[80], *p;
|
||||||
|
|
||||||
|
j = strlen(filename);
|
||||||
|
p = (char *) filename + j;
|
||||||
|
|
||||||
|
/* FIXME need to handle subdirectories /dev/cua/...
|
||||||
|
SCO Unix use lowercase all the time
|
||||||
|
taj
|
||||||
|
*/
|
||||||
|
while (*(p - 1) != '/' && j-- != 1) {
|
||||||
|
#if defined ( __unixware__ )
|
||||||
|
*p = tolower(*p);
|
||||||
|
#endif /* __unixware__ */
|
||||||
|
p--;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(file, "%s/LCK..%s", LOCKDIR, p);
|
||||||
|
|
||||||
|
if (check_lock_status(filename)) {
|
||||||
|
printf("fhs_lock() lockstatus fail\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
fd = open(file, O_CREAT | O_WRONLY | O_EXCL, 0444);
|
||||||
|
|
||||||
|
if (fd < 0) {
|
||||||
|
printf(
|
||||||
|
"RXTX fhs_lock() Error: creating lock file: %s: %s\n",
|
||||||
|
file, strerror(errno));
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(lockinfo, "%10d\n", (int) getpid());
|
||||||
|
printf("fhs_lock: creating lockfile: %s\n", lockinfo);
|
||||||
|
write(fd, lockinfo, 11);
|
||||||
|
close(fd);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
uucp_lock
|
||||||
|
accept: char * filename. Device to be locked
|
||||||
|
perform: Try to get a uucp_lock
|
||||||
|
return: int 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
The File System Hierarchy Standard
|
||||||
|
http://www.pathname.com/fhs/
|
||||||
|
UUCP Lock Files
|
||||||
|
http://docs.freebsd.org/info/uucp/uucp.info.UUCP_Lock_Files.html
|
||||||
|
FSSTND
|
||||||
|
ftp://tsx-11.mit.edu/pub/linux/docs/linux-standards/fsstnd/
|
||||||
|
Proposed Changes to the File System Hierarchy Standard
|
||||||
|
ftp://scicom.alphacdc.com/pub/linux/devlock-0.X.tgz
|
||||||
|
"UNIX Network Programming", W. Richard Stevens,
|
||||||
|
Prentice-Hall, 1990, pages 96-101.
|
||||||
|
There is much to do here.
|
||||||
|
1) UUCP style locks (done)
|
||||||
|
/var/spool/uucp
|
||||||
|
2) SVR4 locks
|
||||||
|
/var/spool/locks
|
||||||
|
3) FSSTND locks (done)
|
||||||
|
/var/lock
|
||||||
|
4) handle stale locks (done except kermit locks)
|
||||||
|
5) handle minicom lockfile contents (FSSTND?)
|
||||||
|
" 16929 minicom root\n" (done)
|
||||||
|
6) there are other Lock conventions that use Major and Minor
|
||||||
|
numbers...
|
||||||
|
7) Stevens recommends LCK..<pid>
|
||||||
|
most are caught above. If they turn out to be problematic
|
||||||
|
rather than an exercise, we will handle them.
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int uucp_lock(const char *filename, int pid) {
|
||||||
|
char lockfilename[80], lockinfo[12];
|
||||||
|
char name[80];
|
||||||
|
int fd;
|
||||||
|
struct stat buf;
|
||||||
|
|
||||||
|
printf("uucp_lock( %s );\n", filename);
|
||||||
|
|
||||||
|
if (check_lock_status(filename)) {
|
||||||
|
printf("RXTX uucp check_lock_status true\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (stat(LOCKDIR, &buf) != 0) {
|
||||||
|
printf("RXTX uucp_lock() could not find lock directory.\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (stat(filename, &buf) != 0) {
|
||||||
|
printf("RXTX uucp_lock() could not find device.\n");
|
||||||
|
printf("uucp_lock: device was %s\n", name);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(lockfilename, "%s/LK.%03d.%03d.%03d",
|
||||||
|
LOCKDIR,
|
||||||
|
(int) major(buf.st_dev),
|
||||||
|
(int) major(buf.st_rdev),
|
||||||
|
(int) minor(buf.st_rdev)
|
||||||
|
);
|
||||||
|
sprintf(lockinfo, "%10d\n", (int) getpid());
|
||||||
|
|
||||||
|
if (stat(lockfilename, &buf) == 0) {
|
||||||
|
printf("RXTX uucp_lock() %s is there\n",
|
||||||
|
lockfilename);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
fd = open(lockfilename, O_CREAT | O_WRONLY | O_EXCL, 0444);
|
||||||
|
|
||||||
|
if (fd < 0) {
|
||||||
|
printf(
|
||||||
|
"RXTX uucp_lock() Error: creating lock file: %s\n",
|
||||||
|
lockfilename);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
write(fd, lockinfo, 11);
|
||||||
|
close(fd);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
check_lock_status
|
||||||
|
accept: the lock name in question
|
||||||
|
perform: Make sure everything is sane
|
||||||
|
return: 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int check_lock_status(const char *filename) {
|
||||||
|
struct stat buf;
|
||||||
|
/* First, can we find the directory? */
|
||||||
|
|
||||||
|
if (stat(LOCKDIR, &buf) != 0) {
|
||||||
|
printf("check_lock_status: could not find lock directory.\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* OK. Are we able to write to it? If not lets bail */
|
||||||
|
|
||||||
|
if (check_group_uucp()) {
|
||||||
|
printf("check_lock_status: No permission to create lock file.\nplease see: How can I use Lock Files with rxtx? in INSTALL\n");
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* is the device alread locked */
|
||||||
|
|
||||||
|
if (is_device_locked(filename)) {
|
||||||
|
printf("check_lock_status: device is locked by another application\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
fhs_unlock
|
||||||
|
accept: The name of the device to unlock
|
||||||
|
perform: delete the lock file
|
||||||
|
return: none
|
||||||
|
exceptions: none
|
||||||
|
comments: This is for linux only currently. I see SVR4 does this
|
||||||
|
differently and there are other proposed changes to the
|
||||||
|
Filesystem Hierachy Standard
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
void fhs_unlock(const char *filename, int openpid) {
|
||||||
|
char file[80], *p;
|
||||||
|
int i;
|
||||||
|
|
||||||
|
i = strlen(filename);
|
||||||
|
p = (char *) filename + i;
|
||||||
|
|
||||||
|
/* FIXME need to handle subdirectories /dev/cua/... */
|
||||||
|
while (*(p - 1) != '/' && i-- != 1) {
|
||||||
|
p--;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(file, "%s/LCK..%s", LOCKDIR, p);
|
||||||
|
|
||||||
|
if (!check_lock_pid(file, openpid)) {
|
||||||
|
unlink(file);
|
||||||
|
printf("fhs_unlock: Removing LockFile\n");
|
||||||
|
} else {
|
||||||
|
printf("fhs_unlock: Unable to remove LockFile\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
uucp_unlock
|
||||||
|
accept: char *filename the device that is locked
|
||||||
|
perform: remove the uucp lockfile if it exists
|
||||||
|
return: none
|
||||||
|
exceptions: none
|
||||||
|
comments: http://docs.freebsd.org/info/uucp/uucp.info.UUCP_Lock_Files.html
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
void uucp_unlock(const char *filename, int openpid) {
|
||||||
|
struct stat buf;
|
||||||
|
char file[80];
|
||||||
|
/* FIXME */
|
||||||
|
|
||||||
|
printf("uucp_unlock( %s );\n", filename);
|
||||||
|
|
||||||
|
if (stat(filename, &buf) != 0) {
|
||||||
|
/* hmm the file is not there? */
|
||||||
|
printf("uucp_unlock() no such device\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(file, LOCKDIR"/LK.%03d.%03d.%03d",
|
||||||
|
(int) major(buf.st_dev),
|
||||||
|
(int) major(buf.st_rdev),
|
||||||
|
(int) minor(buf.st_rdev)
|
||||||
|
);
|
||||||
|
|
||||||
|
if (stat(file, &buf) != 0) {
|
||||||
|
/* hmm the file is not there? */
|
||||||
|
printf("uucp_unlock no such lockfile\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!check_lock_pid(file, openpid)) {
|
||||||
|
printf("uucp_unlock: unlinking %s\n", file);
|
||||||
|
unlink(file);
|
||||||
|
} else {
|
||||||
|
printf("uucp_unlock: unlinking failed %s\n", file);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
check_lock_pid
|
||||||
|
accept: the name of the lockfile
|
||||||
|
perform: make sure the lock file is ours.
|
||||||
|
return: 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int check_lock_pid(const char *file, int openpid) {
|
||||||
|
int fd, lockpid;
|
||||||
|
char pid_buffer[12];
|
||||||
|
|
||||||
|
fd = open(file, O_RDONLY);
|
||||||
|
|
||||||
|
if (fd < 0) {
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (read(fd, pid_buffer, 11) < 0) {
|
||||||
|
close(fd);
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
close(fd);
|
||||||
|
pid_buffer[11] = '\0';
|
||||||
|
lockpid = atol(pid_buffer);
|
||||||
|
|
||||||
|
/* Native threads JVM's have multiple pids */
|
||||||
|
if (lockpid != getpid() && lockpid != getppid() && lockpid != openpid) {
|
||||||
|
printf("check_lock_pid: lock = %s pid = %i gpid=%i openpid=%i\n",
|
||||||
|
pid_buffer, (int) getpid(), (int) getppid(), openpid);
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return (0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
check_group_uucp
|
||||||
|
accept: none
|
||||||
|
perform: check if the user is root or in group uucp
|
||||||
|
return: 0 on success
|
||||||
|
exceptions: none
|
||||||
|
comments:
|
||||||
|
This checks if the effective user is in group uucp so we can
|
||||||
|
create lock files. If not we give them a warning and bail.
|
||||||
|
If its root we just skip the test.
|
||||||
|
if someone really wants to override this they can use the USER_LOCK_DIRECTORY --not recommended.
|
||||||
|
In a recent change RedHat 7.2 decided to use group lock.
|
||||||
|
In order to get around this we just check the group id
|
||||||
|
of the lock directory.
|
||||||
|
* Modified to support Debian *
|
||||||
|
The problem was that checking the ownership of the lock file
|
||||||
|
dir is not enough, in the sense that even if the current user
|
||||||
|
is not in the group of the lock directory if the lock
|
||||||
|
directory has 777 permissions the lock file can be anyway
|
||||||
|
created. My solution is simply to try to create a tmp file
|
||||||
|
there and if it works then we can go on. Here is my code that
|
||||||
|
I tried and seems to work.
|
||||||
|
Villa Valerio <valerio.villa@siemens.com>
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int check_group_uucp() {
|
||||||
|
|
||||||
|
#ifndef USER_LOCK_DIRECTORY
|
||||||
|
FILE *testLockFile ;
|
||||||
|
char testLockFileDirName[] = LOCKDIR;
|
||||||
|
char testLockFileName[] = "tmpXXXXXX";
|
||||||
|
char *testLockAbsFileName;
|
||||||
|
|
||||||
|
testLockAbsFileName = calloc(strlen(testLockFileDirName)
|
||||||
|
+ strlen(testLockFileName) + 2, sizeof(char));
|
||||||
|
|
||||||
|
if (NULL == testLockAbsFileName) {
|
||||||
|
printf("check_group_uucp(): Insufficient memory");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
strcat(testLockAbsFileName, testLockFileDirName);
|
||||||
|
strcat(testLockAbsFileName, "/");
|
||||||
|
strcat(testLockAbsFileName, testLockFileName);
|
||||||
|
|
||||||
|
if (-1 == mkstemp(testLockAbsFileName)) {
|
||||||
|
free(testLockAbsFileName);
|
||||||
|
printf("check_group_uucp(): mktemp malformed string - \
|
||||||
|
should not happen");
|
||||||
|
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
testLockFile = fopen(testLockAbsFileName, "w+");
|
||||||
|
|
||||||
|
if (NULL == testLockFile) {
|
||||||
|
printf("check_group_uucp(): error testing lock file "
|
||||||
|
"creation Error details:");
|
||||||
|
printf("%s\n", strerror(errno));
|
||||||
|
free(testLockAbsFileName);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
fclose(testLockFile);
|
||||||
|
unlink(testLockAbsFileName);
|
||||||
|
free(testLockAbsFileName);
|
||||||
|
|
||||||
|
#endif /* USER_LOCK_DIRECTORY */
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_OLD_CHECK_GROUP_UUCP
|
||||||
|
int check_group_uucp() {
|
||||||
|
#ifndef USER_LOCK_DIRECTORY
|
||||||
|
int group_count;
|
||||||
|
struct passwd *user = getpwuid(geteuid());
|
||||||
|
struct stat buf;
|
||||||
|
char msg[80];
|
||||||
|
gid_t list[ NGROUPS_MAX ];
|
||||||
|
|
||||||
|
if (stat(LOCKDIR, &buf)) {
|
||||||
|
sprintf(msg, "check_group_uucp: Can not find Lock Directory: %s\n", LOCKDIR);
|
||||||
|
printf(msg);
|
||||||
|
return (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
group_count = getgroups(NGROUPS_MAX, list);
|
||||||
|
list[ group_count ] = geteuid();
|
||||||
|
|
||||||
|
/* JJO changes start */
|
||||||
|
if (user == NULL) {
|
||||||
|
printf("Not able to get user groups.\n");
|
||||||
|
return 1;
|
||||||
|
} else
|
||||||
|
|
||||||
|
/* JJO changes stop */
|
||||||
|
|
||||||
|
|
||||||
|
if (user->pw_gid) {
|
||||||
|
while (group_count >= 0 && buf.st_gid != list[ group_count ]) {
|
||||||
|
group_count--;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (buf.st_gid == list[ group_count ]) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(msg, "%i %i\n", buf.st_gid, list[ group_count ]);
|
||||||
|
printf(msg);
|
||||||
|
printf(UUCP_ERROR);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
/*
|
||||||
|
if( strcmp( user->pw_name, "root" ) )
|
||||||
|
{
|
||||||
|
while( *g->gr_mem )
|
||||||
|
{
|
||||||
|
if( !strcmp( *g->gr_mem, user->pw_name ) )
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
(void) *g->gr_mem++;
|
||||||
|
}
|
||||||
|
if( !*g->gr_mem )
|
||||||
|
{
|
||||||
|
printf( UUCP_ERROR );
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
#endif /* USER_LOCK_DIRECTORY */
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif /* USE_OLD_CHECK_GROUP_UUCP */
|
||||||
|
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
The following should be able to follow symbolic links. I think the stat
|
||||||
|
method used below will work on more systems. This was found while looking
|
||||||
|
for information.
|
||||||
|
* realpath() doesn't exist on all of the systems my code has to run
|
||||||
|
on (HP-UX 9.x, specifically)
|
||||||
|
----------------------------------------------------------
|
||||||
|
int different_from_LOCKDIR(const char* ld)
|
||||||
|
{
|
||||||
|
char real_ld[MAXPATHLEN];
|
||||||
|
char real_LOCKDIR[MAXPATHLEN];
|
||||||
|
if (strncmp(ld, LOCKDIR, strlen(ld)) == 0)
|
||||||
|
return 0;
|
||||||
|
if (realpath(ld, real_ld) == NULL)
|
||||||
|
return 1;
|
||||||
|
if (realpath(LOCKDIR, real_LOCKDIR) == NULL)
|
||||||
|
return 1;
|
||||||
|
if (strncmp(real_ld, real_LOCKDIR, strlen(real_ld)) == 0)
|
||||||
|
return 0;
|
||||||
|
else
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*----------------------------------------------------------
|
||||||
|
is_device_locked
|
||||||
|
accept: char * filename. The device in question including the path.
|
||||||
|
perform: see if one of the many possible lock files is aready there
|
||||||
|
if there is a stale lock, remove it.
|
||||||
|
return: 1 if the device is locked or somethings wrong.
|
||||||
|
0 if its possible to create our own lock file.
|
||||||
|
exceptions: none
|
||||||
|
comments: check if the device is already locked
|
||||||
|
----------------------------------------------------------*/
|
||||||
|
int is_device_locked(const char *port_filename) {
|
||||||
|
const char *lockdirs[] = { "/etc/locks", "/usr/spool/kermit",
|
||||||
|
"/usr/spool/locks", "/usr/spool/uucp", "/usr/spool/uucp/",
|
||||||
|
"/usr/spool/uucp/LCK", "/var/lock", "/var/lock/modem",
|
||||||
|
"/var/spool/lock", "/var/spool/locks", "/var/spool/uucp",
|
||||||
|
LOCKDIR, NULL
|
||||||
|
};
|
||||||
|
const char *lockprefixes[] = { "LCK..", "lk..", "LK.", NULL };
|
||||||
|
char *p, file[80], pid_buffer[20];
|
||||||
|
int i = 0, j, k, fd, pid;
|
||||||
|
struct stat buf, buf2, lockbuf;
|
||||||
|
|
||||||
|
j = strlen(port_filename);
|
||||||
|
p = (char *) port_filename + j;
|
||||||
|
|
||||||
|
while (*(p - 1) != '/' && j-- != 1) {
|
||||||
|
p--;
|
||||||
|
}
|
||||||
|
|
||||||
|
stat(LOCKDIR, &lockbuf);
|
||||||
|
|
||||||
|
while (lockdirs[i]) {
|
||||||
|
/*
|
||||||
|
Look for lockfiles in all known places other than the
|
||||||
|
defined lock directory for this system
|
||||||
|
report any unexpected lockfiles.
|
||||||
|
Is the suspect lockdir there?
|
||||||
|
if it is there is it not the expected lock dir?
|
||||||
|
*/
|
||||||
|
if (!stat(lockdirs[i], &buf2) &&
|
||||||
|
buf2.st_ino != lockbuf.st_ino &&
|
||||||
|
strncmp(lockdirs[i], LOCKDIR, strlen(lockdirs[i]))) {
|
||||||
|
j = strlen(port_filename);
|
||||||
|
p = (char *) port_filename + j;
|
||||||
|
|
||||||
|
/*
|
||||||
|
SCO Unix use lowercase all the time
|
||||||
|
taj
|
||||||
|
*/
|
||||||
|
while (*(p - 1) != '/' && j-- != 1) {
|
||||||
|
#if defined ( __unixware__ )
|
||||||
|
*p = tolower(*p);
|
||||||
|
#endif /* __unixware__ */
|
||||||
|
p--;
|
||||||
|
}
|
||||||
|
|
||||||
|
k = 0;
|
||||||
|
|
||||||
|
while (lockprefixes[k]) {
|
||||||
|
/* FHS style */
|
||||||
|
sprintf(file, "%s/%s%s", lockdirs[i],
|
||||||
|
lockprefixes[k], p);
|
||||||
|
|
||||||
|
if (stat(file, &buf) == 0) {
|
||||||
|
// sprintf( message, UNEXPECTED_LOCK_FILE,
|
||||||
|
// file );
|
||||||
|
// printf( message );
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* UUCP style */
|
||||||
|
stat(port_filename, &buf);
|
||||||
|
sprintf(file, "%s/%s%03d.%03d.%03d",
|
||||||
|
lockdirs[i],
|
||||||
|
lockprefixes[k],
|
||||||
|
(int) major(buf.st_dev),
|
||||||
|
(int) major(buf.st_rdev),
|
||||||
|
(int) minor(buf.st_rdev)
|
||||||
|
);
|
||||||
|
|
||||||
|
if (stat(file, &buf) == 0) {
|
||||||
|
// sprintf( message, UNEXPECTED_LOCK_FILE,
|
||||||
|
// file );
|
||||||
|
// printf( message );
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
k++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
OK. We think there are no unexpect lock files for this device
|
||||||
|
Lets see if there any stale lock files that need to be
|
||||||
|
removed.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef FHS
|
||||||
|
/* FHS standard locks */
|
||||||
|
i = strlen(port_filename);
|
||||||
|
p = (char *) port_filename + i;
|
||||||
|
|
||||||
|
while (*(p - 1) != '/' && i-- != 1) {
|
||||||
|
#if defined ( __unixware__ )
|
||||||
|
*p = tolower(*p);
|
||||||
|
#endif /* __unixware__ */
|
||||||
|
p--;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(file, "%s/%s%s", LOCKDIR, LOCKFILEPREFIX, p);
|
||||||
|
#else
|
||||||
|
|
||||||
|
/* UUCP standard locks */
|
||||||
|
if (stat(port_filename, &buf) != 0) {
|
||||||
|
printf("RXTX is_device_locked() could not find device.\n");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(file, "%s/LK.%03d.%03d.%03d",
|
||||||
|
LOCKDIR,
|
||||||
|
(int) major(buf.st_dev),
|
||||||
|
(int) major(buf.st_rdev),
|
||||||
|
(int) minor(buf.st_rdev)
|
||||||
|
);
|
||||||
|
|
||||||
|
#endif /* FHS */
|
||||||
|
|
||||||
|
if (stat(file, &buf) == 0) {
|
||||||
|
|
||||||
|
/* check if its a stale lock */
|
||||||
|
fd = open(file, O_RDONLY);
|
||||||
|
read(fd, pid_buffer, 11);
|
||||||
|
/* FIXME null terminiate pid_buffer? need to check in Solaris */
|
||||||
|
close(fd);
|
||||||
|
sscanf(pid_buffer, "%d", &pid);
|
||||||
|
|
||||||
|
if (kill((pid_t) pid, 0) && errno == ESRCH) {
|
||||||
|
printf(
|
||||||
|
"RXTX Warning: Removing stale lock file. %s\n",
|
||||||
|
file);
|
||||||
|
|
||||||
|
if (unlink(file) != 0) {
|
||||||
|
printf("RXTX Error: Unable to \
|
||||||
|
remove stale lock file: %s\n",
|
||||||
|
file
|
||||||
|
);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif /* WIN32 */
|
||||||
|
|
|
@ -0,0 +1,241 @@
|
||||||
|
/*
|
||||||
|
* lock.h
|
||||||
|
*
|
||||||
|
* Created on: 28 Mar 2018
|
||||||
|
* Author: Tony
|
||||||
|
* E-Mail: Tony@gmail.com
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef LOCK_H_
|
||||||
|
#define LOCK_H_
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef HAVE_SYS_FILE_H
|
||||||
|
# include <sys/file.h>
|
||||||
|
#endif /* HAVE_SYS_FILE_H */
|
||||||
|
#ifdef LFS /* File Lock Server */
|
||||||
|
# include <sys/socket.h>
|
||||||
|
# include <netinet/in.h>
|
||||||
|
# include <arpa/inet.h>
|
||||||
|
#endif /* FLS */
|
||||||
|
#if defined(__linux__)
|
||||||
|
# include <linux/types.h> /* fix for linux-2.3.4? kernels */
|
||||||
|
# include <linux/serial.h>
|
||||||
|
# include <linux/version.h>
|
||||||
|
#endif /* __linux__ */
|
||||||
|
#if defined(__sun__)
|
||||||
|
# include <sys/filio.h>
|
||||||
|
# include <sys/mkdev.h>
|
||||||
|
#endif /* __sun__ */
|
||||||
|
#if defined(__hpux__)
|
||||||
|
# include <sys/modem.h>
|
||||||
|
#endif /* __hpux__ */
|
||||||
|
/* FIXME -- new file */
|
||||||
|
#if defined(__APPLE__)
|
||||||
|
# include <CoreFoundation/CoreFoundation.h>
|
||||||
|
# include <IOKit/IOKitLib.h>
|
||||||
|
# include <IOKit/serial/IOSerialKeys.h>
|
||||||
|
# include <IOKit/IOBSD.h>
|
||||||
|
#endif /* __APPLE__ */
|
||||||
|
#ifdef __unixware__
|
||||||
|
# include <sys/filio.h>
|
||||||
|
#endif /* __unixware__ */
|
||||||
|
#ifdef HAVE_PWD_H
|
||||||
|
#include <pwd.h>
|
||||||
|
#endif /* HAVE_PWD_H */
|
||||||
|
#ifdef HAVE_GRP_H
|
||||||
|
#include <grp.h>
|
||||||
|
#endif /* HAVE_GRP_H */
|
||||||
|
#include <math.h>
|
||||||
|
#ifdef LIBLOCKDEV
|
||||||
|
#include <lockdev.h>
|
||||||
|
#endif /* LIBLOCKDEV */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Ports known on the OS */
|
||||||
|
#if defined(__linux__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/var/lock"
|
||||||
|
# define LOCKFILEPREFIX "LCK.."
|
||||||
|
# define FHS
|
||||||
|
#endif /* __linux__ */
|
||||||
|
#if defined(__QNX__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR ""
|
||||||
|
# define LOCKFILEPREFIX ""
|
||||||
|
#endif /* qnx */
|
||||||
|
#if defined(__sgi__) || defined(sgi)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/usr/spool/uucp"
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __sgi__ || sgi */
|
||||||
|
#if defined(__FreeBSD__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/var/spool/lock"
|
||||||
|
# define LOCKFILEPREFIX "LK.."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __FreeBSD__ */
|
||||||
|
#if defined(__APPLE__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
/*# define LOCKDIR "/var/spool/uucp"*/
|
||||||
|
# define LOCKDIR "/var/lock"
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __APPLE__ */
|
||||||
|
#if defined(__NetBSD__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/var/lock"
|
||||||
|
/*# define LOCKDIR "/usr/spool/uucp"*/
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __NetBSD__ */
|
||||||
|
#if defined(__unixware__)
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
/* really this only fully works for OpenServer */
|
||||||
|
# define LOCKDIR "/var/spool/uucp/"
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
/*
|
||||||
|
this needs work....
|
||||||
|
Jonathan Schilling <jls@caldera.com> writes:
|
||||||
|
This is complicated because as I said in my previous mail, there are
|
||||||
|
two kinds of SCO operating systems.
|
||||||
|
The one that most people want gnu.io for, including the guy who
|
||||||
|
asked the mailing list about SCO support a few days ago, is Open Server
|
||||||
|
(a/k/a "SCO UNIX"), which is SVR3-based. This uses old-style uucp locks,
|
||||||
|
of the form LCK..tty0a. That's what I implemented in the RXTX port I did,
|
||||||
|
and it works correctly.
|
||||||
|
The other SCO/Caldera OS, UnixWare/Open UNIX, uses the new-style
|
||||||
|
SVR4 locks, of the form LK.123.123.123. These OSes are a lot like
|
||||||
|
Solaris (UnixWare/Open UNIX come from AT&T SVR4 which had a joint
|
||||||
|
The other SCO/Caldera OS, UnixWare/Open UNIX, uses the new-style
|
||||||
|
SVR4 locks, of the form LK.123.123.123. These OSes are a lot like
|
||||||
|
Solaris (UnixWare/Open UNIX come from AT&T SVR4 which had a joint
|
||||||
|
heritage with Sun way back when). I saw that you added support
|
||||||
|
for this form of lock by RXTX 1.4-10 ... but it gets messy because,
|
||||||
|
as I said before, we use the same binary gnu.io files for both
|
||||||
|
UnixWare/Open UNIX and OpenServer. Thus we can't #ifdef one or the
|
||||||
|
other; it would have to be a runtime test. Your code and your macros
|
||||||
|
aren't set up for doing this (understandably!). So I didn't implement
|
||||||
|
these; the gnu.io locks won't fully work on UnixWare/Open UNIX
|
||||||
|
as a result, which I mentioned in the Release Notes.
|
||||||
|
What I would suggest is that you merge in the old-style LCK..tty0a lock
|
||||||
|
code that I used, since this will satisfy 90% of the SCO users. Then
|
||||||
|
I'll work on some way of getting UnixWare/Open UNIX locking to work
|
||||||
|
correctly, and give you those changes at a later date.
|
||||||
|
Jonathan
|
||||||
|
FIXME The lock type could be passed with -DOLDUUCP or -DUUCP based on
|
||||||
|
os.name in configure.in or perhaps system defines could determine the lock
|
||||||
|
type.
|
||||||
|
Trent
|
||||||
|
*/
|
||||||
|
# define OLDUUCP
|
||||||
|
#endif
|
||||||
|
#if defined(__hpux__)
|
||||||
|
/* modif cath */
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/var/spool/uucp"
|
||||||
|
# define LOCKFILEPREFIX "LCK."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __hpux__ */
|
||||||
|
#if defined(__osf__) /* Digital Unix */
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR ""
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __osf__ */
|
||||||
|
#if defined(__sun__) /* Solaris */
|
||||||
|
# define DEVICEDIR "/dev/"
|
||||||
|
# define LOCKDIR "/var/spool/locks"
|
||||||
|
# define LOCKFILEPREFIX "LK."
|
||||||
|
/*
|
||||||
|
# define UUCP
|
||||||
|
*/
|
||||||
|
#endif /* __sun__ */
|
||||||
|
#if defined(__BEOS__)
|
||||||
|
# define DEVICEDIR "/dev/ports/"
|
||||||
|
# define LOCKDIR ""
|
||||||
|
# define LOCKFILEPREFIX ""
|
||||||
|
# define UUCP
|
||||||
|
#endif /* __BEOS__ */
|
||||||
|
#if defined(WIN32)
|
||||||
|
# define DEVICEDIR "//./"
|
||||||
|
# define LOCKDIR ""
|
||||||
|
# define LOCKFILEPREFIX ""
|
||||||
|
#endif /* WIN32 */
|
||||||
|
|
||||||
|
/* allow people to override the directories */
|
||||||
|
/* #define USER_LOCK_DIRECTORY "/home/tjarvi/1.5/build" */
|
||||||
|
#ifdef USER_LOCK_DIRECTORY
|
||||||
|
# define LOCKDIR USER_LOCK_DIRECTORY
|
||||||
|
#endif /* USER_LOCK_DIRECTORY */
|
||||||
|
|
||||||
|
#ifdef DISABLE_LOCKFILES
|
||||||
|
#undef UUCP
|
||||||
|
#undef FHS
|
||||||
|
#undef OLDUUCP
|
||||||
|
#endif /* DISABLE_LOCKFILES */
|
||||||
|
|
||||||
|
/* That should be all you need to look at in this file for porting */
|
||||||
|
#ifdef LFS /* Use a Lock File Server */
|
||||||
|
# define LOCK lfs_lock
|
||||||
|
# define UNLOCK lfs_unlock
|
||||||
|
#elif defined(UUCP)
|
||||||
|
# define LOCK uucp_lock
|
||||||
|
# define UNLOCK uucp_unlock
|
||||||
|
#elif defined(OLDUUCP)
|
||||||
|
/*
|
||||||
|
We can handle the old style if needed here see __unixware__ above.
|
||||||
|
defaulting to rxtx-1.4-8 behavior for now.
|
||||||
|
see also __sco__ in SerialImp.c when changing this for a possible
|
||||||
|
bug
|
||||||
|
FIXME
|
||||||
|
*/
|
||||||
|
# define LOCK fhs_lock
|
||||||
|
# define UNLOCK fhs_unlock
|
||||||
|
#elif defined(FHS)
|
||||||
|
#ifdef LIBLOCKDEV
|
||||||
|
# define LOCK lib_lock_dev_lock
|
||||||
|
# define UNLOCK lib_lock_dev_unlock
|
||||||
|
#else
|
||||||
|
# define LOCK fhs_lock
|
||||||
|
# define UNLOCK fhs_unlock
|
||||||
|
#endif /* LIBLOCKDEV */
|
||||||
|
#else
|
||||||
|
# define LOCK system_does_not_lock
|
||||||
|
# define UNLOCK system_does_not_unlock
|
||||||
|
#endif /* UUCP */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//#ifndef __WIN32__
|
||||||
|
//#define UUCP_LOCK_DIR "/var/lock"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
//int uucp_lock( const char *file);
|
||||||
|
//int uucp_unlock(void);
|
||||||
|
int check_group_uucp();
|
||||||
|
int check_lock_pid(const char *file, int openpid);
|
||||||
|
int lock_device(const char *);
|
||||||
|
void unlock_device(const char *);
|
||||||
|
int is_device_locked(const char *);
|
||||||
|
int check_lock_status(const char *);
|
||||||
|
int lfs_unlock(const char *, int);
|
||||||
|
int lfs_lock(const char *, int);
|
||||||
|
int lib_lock_dev_unlock(const char *, int);
|
||||||
|
int lib_lock_dev_lock(const char *, int);
|
||||||
|
void fhs_unlock(const char *, int);
|
||||||
|
int fhs_lock(const char *, int);
|
||||||
|
void uucp_unlock(const char *, int);
|
||||||
|
int uucp_lock(const char *, int);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//#endif
|
||||||
|
|
||||||
|
#endif /* LOCK_H_ */
|
|
@ -0,0 +1,27 @@
|
||||||
|
#pragma once
|
||||||
|
// libc dep
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <time.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
|
||||||
|
// libc++ dep
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
// linux specific
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <sys/select.h>
|
||||||
|
#include <time.h>
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,162 @@
|
||||||
|
#if !defined(_WIN32)
|
||||||
|
|
||||||
|
#ifndef SERIAL_IMPL_UNIX_H
|
||||||
|
#define SERIAL_IMPL_UNIX_H
|
||||||
|
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#include <termios.h>
|
||||||
|
#include <core/serial/serial.h>
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
using std::size_t;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
|
||||||
|
class MillisecondTimer {
|
||||||
|
public:
|
||||||
|
explicit MillisecondTimer(const uint32_t millis);
|
||||||
|
int64_t remaining();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static timespec timespec_now();
|
||||||
|
timespec expiry;
|
||||||
|
};
|
||||||
|
|
||||||
|
class Serial::SerialImpl {
|
||||||
|
public:
|
||||||
|
explicit SerialImpl(const string &port,
|
||||||
|
unsigned long baudrate,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity,
|
||||||
|
stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
virtual ~SerialImpl();
|
||||||
|
|
||||||
|
bool open();
|
||||||
|
|
||||||
|
Serial::SerialPortError getSystemError(int systemErrorCode) const;
|
||||||
|
|
||||||
|
void close();
|
||||||
|
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
size_t available();
|
||||||
|
|
||||||
|
bool waitReadable(uint32_t timeout);
|
||||||
|
|
||||||
|
void waitByteTimes(size_t count);
|
||||||
|
|
||||||
|
int waitfordata(size_t data_count, uint32_t timeout, size_t *returned_size);
|
||||||
|
|
||||||
|
size_t read(uint8_t *buf, size_t size = 1);
|
||||||
|
|
||||||
|
size_t write(const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
|
||||||
|
void flush();
|
||||||
|
|
||||||
|
void flushInput();
|
||||||
|
|
||||||
|
void flushOutput();
|
||||||
|
|
||||||
|
void sendBreak(int duration);
|
||||||
|
|
||||||
|
bool setBreak(bool level);
|
||||||
|
|
||||||
|
bool setRTS(bool level);
|
||||||
|
|
||||||
|
bool setDTR(bool level);
|
||||||
|
|
||||||
|
bool waitForChange();
|
||||||
|
|
||||||
|
bool getCTS();
|
||||||
|
|
||||||
|
bool getDSR();
|
||||||
|
|
||||||
|
bool getRI();
|
||||||
|
|
||||||
|
bool getCD();
|
||||||
|
|
||||||
|
uint32_t getByteTime();
|
||||||
|
|
||||||
|
void setPort(const string &port);
|
||||||
|
|
||||||
|
string getPort() const;
|
||||||
|
|
||||||
|
void setTimeout(Timeout &timeout);
|
||||||
|
|
||||||
|
Timeout getTimeout() const;
|
||||||
|
|
||||||
|
bool setBaudrate(unsigned long baudrate);
|
||||||
|
|
||||||
|
bool setStandardBaudRate(speed_t baudrate);
|
||||||
|
|
||||||
|
bool setCustomBaudRate(unsigned long baudrate);
|
||||||
|
|
||||||
|
unsigned long getBaudrate() const;
|
||||||
|
|
||||||
|
bool setBytesize(bytesize_t bytesize);
|
||||||
|
|
||||||
|
bytesize_t getBytesize() const;
|
||||||
|
|
||||||
|
bool setParity(parity_t parity);
|
||||||
|
|
||||||
|
parity_t getParity() const;
|
||||||
|
|
||||||
|
bool setStopbits(stopbits_t stopbits);
|
||||||
|
|
||||||
|
stopbits_t getStopbits() const;
|
||||||
|
|
||||||
|
bool setFlowcontrol(flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
flowcontrol_t getFlowcontrol() const;
|
||||||
|
|
||||||
|
bool setTermios(const termios *tio);
|
||||||
|
|
||||||
|
bool getTermios(termios *tio);
|
||||||
|
|
||||||
|
int readLock();
|
||||||
|
|
||||||
|
int readUnlock();
|
||||||
|
|
||||||
|
int writeLock();
|
||||||
|
|
||||||
|
int writeUnlock();
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
string port_; // Path to the file descriptor
|
||||||
|
int fd_; // The current file descriptor
|
||||||
|
pid_t pid;
|
||||||
|
|
||||||
|
bool is_open_;
|
||||||
|
bool xonxoff_;
|
||||||
|
bool rtscts_;
|
||||||
|
|
||||||
|
Timeout timeout_; // Timeout for read operations
|
||||||
|
unsigned long baudrate_; // Baudrate
|
||||||
|
uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte
|
||||||
|
|
||||||
|
parity_t parity_; // Parity
|
||||||
|
bytesize_t bytesize_; // Size of the bytes
|
||||||
|
stopbits_t stopbits_; // Stop Bits
|
||||||
|
flowcontrol_t flowcontrol_; // Flow Control
|
||||||
|
|
||||||
|
// Mutex used to lock the read functions
|
||||||
|
pthread_mutex_t read_mutex;
|
||||||
|
// Mutex used to lock the write functions
|
||||||
|
pthread_mutex_t write_mutex;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // SERIAL_IMPL_UNIX_H
|
||||||
|
|
||||||
|
#endif // !defined(_WIN32)
|
|
@ -0,0 +1,5 @@
|
||||||
|
aux_include_directory(. HDRS)
|
||||||
|
aux_src_directory(. SRCS)
|
||||||
|
add_to_ydlidar_headers(${HDRS})
|
||||||
|
add_to_ydlidar_sources(${SRCS})
|
||||||
|
|
|
@ -0,0 +1,196 @@
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#pragma comment(lib, "setupapi.lib")
|
||||||
|
#ifdef QT_VERSION
|
||||||
|
#include <QtGlobal>
|
||||||
|
#if (QT_VERSION <= QT_VERSION_CHECK(5,9,0))
|
||||||
|
#undef UNICODE
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#undef UNICODE
|
||||||
|
#endif
|
||||||
|
#include <core/serial/serial.h>
|
||||||
|
#include <tchar.h>
|
||||||
|
#include <windows.h>
|
||||||
|
#include <setupapi.h>
|
||||||
|
#include <initguid.h>
|
||||||
|
#include <devguid.h>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
using ydlidar::core::serial::PortInfo;
|
||||||
|
using std::vector;
|
||||||
|
using std::string;
|
||||||
|
using namespace ydlidar::core;
|
||||||
|
|
||||||
|
static const DWORD port_name_max_length = 256;
|
||||||
|
static const DWORD friendly_name_max_length = 256;
|
||||||
|
static const DWORD hardware_id_max_length = 256;
|
||||||
|
static const DWORD device_id_max_length = 256;
|
||||||
|
|
||||||
|
|
||||||
|
// Convert a wide Unicode string to an UTF8 string
|
||||||
|
std::string utf8_encode(const std::wstring &wstr) {
|
||||||
|
int size_needed = WideCharToMultiByte(CP_UTF8, 0, &wstr[0], (int)wstr.size(),
|
||||||
|
NULL, 0, NULL, NULL);
|
||||||
|
std::string strTo(size_needed, 0);
|
||||||
|
WideCharToMultiByte(CP_UTF8, 0, &wstr[0], (int)wstr.size(), &strTo[0],
|
||||||
|
size_needed, NULL, NULL);
|
||||||
|
return strTo;
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<PortInfo>
|
||||||
|
serial::list_ports() {
|
||||||
|
vector<PortInfo> devices_found;
|
||||||
|
|
||||||
|
HDEVINFO device_info_set = SetupDiGetClassDevs(
|
||||||
|
(const GUID *) &GUID_DEVCLASS_PORTS,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
DIGCF_PRESENT);
|
||||||
|
|
||||||
|
unsigned int device_info_set_index = 0;
|
||||||
|
SP_DEVINFO_DATA device_info_data;
|
||||||
|
|
||||||
|
device_info_data.cbSize = sizeof(SP_DEVINFO_DATA);
|
||||||
|
|
||||||
|
while (SetupDiEnumDeviceInfo(device_info_set, device_info_set_index,
|
||||||
|
&device_info_data)) {
|
||||||
|
device_info_set_index++;
|
||||||
|
|
||||||
|
// Get port name
|
||||||
|
|
||||||
|
HKEY hkey = SetupDiOpenDevRegKey(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
DICS_FLAG_GLOBAL,
|
||||||
|
0,
|
||||||
|
DIREG_DEV,
|
||||||
|
KEY_READ);
|
||||||
|
|
||||||
|
TCHAR port_name[port_name_max_length];
|
||||||
|
DWORD port_name_length = port_name_max_length;
|
||||||
|
|
||||||
|
LONG return_code = RegQueryValueEx(
|
||||||
|
hkey,
|
||||||
|
_T("PortName"),
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
(LPBYTE)port_name,
|
||||||
|
&port_name_length);
|
||||||
|
|
||||||
|
RegCloseKey(hkey);
|
||||||
|
|
||||||
|
if (return_code != EXIT_SUCCESS) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (port_name_length > 0 && port_name_length <= port_name_max_length) {
|
||||||
|
port_name[port_name_length - 1] = '\0';
|
||||||
|
} else {
|
||||||
|
port_name[0] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ignore parallel ports
|
||||||
|
|
||||||
|
if (_tcsstr(port_name, _T("LPT")) != NULL) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get port friendly name
|
||||||
|
|
||||||
|
TCHAR friendly_name[friendly_name_max_length];
|
||||||
|
DWORD friendly_name_actual_length = 0;
|
||||||
|
|
||||||
|
BOOL got_friendly_name = SetupDiGetDeviceRegistryProperty(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
SPDRP_FRIENDLYNAME,
|
||||||
|
NULL,
|
||||||
|
(PBYTE)friendly_name,
|
||||||
|
friendly_name_max_length,
|
||||||
|
&friendly_name_actual_length);
|
||||||
|
|
||||||
|
if (got_friendly_name == TRUE && friendly_name_actual_length > 0) {
|
||||||
|
friendly_name[friendly_name_actual_length - 1] = '\0';
|
||||||
|
} else {
|
||||||
|
friendly_name[0] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get hardware ID
|
||||||
|
|
||||||
|
TCHAR hardware_id[hardware_id_max_length];
|
||||||
|
DWORD hardware_id_actual_length = 0;
|
||||||
|
|
||||||
|
BOOL got_hardware_id = SetupDiGetDeviceRegistryProperty(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
SPDRP_HARDWAREID,
|
||||||
|
NULL,
|
||||||
|
(PBYTE)hardware_id,
|
||||||
|
hardware_id_max_length,
|
||||||
|
&hardware_id_actual_length);
|
||||||
|
|
||||||
|
if (got_hardware_id == TRUE && hardware_id_actual_length > 0) {
|
||||||
|
hardware_id[hardware_id_actual_length - 1] = '\0';
|
||||||
|
} else {
|
||||||
|
hardware_id[0] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
TCHAR device_id[device_id_max_length];
|
||||||
|
DWORD device_id_actual_length = 0;
|
||||||
|
|
||||||
|
BOOL got_device_id = SetupDiGetDeviceRegistryProperty(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
SPDRP_LOCATION_INFORMATION,
|
||||||
|
NULL,
|
||||||
|
(PBYTE)device_id,
|
||||||
|
device_id_max_length,
|
||||||
|
&device_id_actual_length);
|
||||||
|
|
||||||
|
if (got_device_id == TRUE && device_id_actual_length > 0) {
|
||||||
|
device_id[device_id_actual_length - 1] = '\0';
|
||||||
|
} else {
|
||||||
|
device_id[0] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef UNICODE
|
||||||
|
std::string portName = utf8_encode(port_name);
|
||||||
|
std::string friendlyName = utf8_encode(friendly_name);
|
||||||
|
std::string hardwareId = utf8_encode(hardware_id);
|
||||||
|
std::string deviceId = utf8_encode(device_id);
|
||||||
|
|
||||||
|
#else
|
||||||
|
std::string portName = port_name;
|
||||||
|
std::string friendlyName = friendly_name;
|
||||||
|
std::string hardwareId = hardware_id;
|
||||||
|
std::string deviceId = device_id;
|
||||||
|
#endif
|
||||||
|
size_t pos = deviceId.find("#");
|
||||||
|
|
||||||
|
if (pos != std::string::npos) {
|
||||||
|
deviceId = deviceId.substr(pos + 1, 4);
|
||||||
|
deviceId = std::to_string(atoi(deviceId.c_str()));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hardwareId.find("VID_10C4&PID_EA60") != std::string::npos ||
|
||||||
|
hardwareId.find("VID_0483&PID_5740") != std::string::npos) {
|
||||||
|
PortInfo port_entry;
|
||||||
|
port_entry.port = portName;
|
||||||
|
port_entry.description = friendlyName;
|
||||||
|
port_entry.hardware_id = hardwareId;
|
||||||
|
port_entry.device_id = deviceId;
|
||||||
|
devices_found.push_back(port_entry);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
SetupDiDestroyDeviceInfoList(device_info_set);
|
||||||
|
|
||||||
|
return devices_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // #if defined(_WIN32)
|
|
@ -0,0 +1,10 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stddef.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <windows.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <process.h>
|
||||||
|
#include <direct.h>
|
||||||
|
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,175 @@
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
#ifndef SERIAL_IMPL_WINDOWS_H
|
||||||
|
#define SERIAL_IMPL_WINDOWS_H
|
||||||
|
|
||||||
|
#include <core/serial/serial.h>
|
||||||
|
#include <time.h>
|
||||||
|
#include <tchar.h>
|
||||||
|
|
||||||
|
#ifndef UNICODE
|
||||||
|
#define UNICODE
|
||||||
|
#define UNICODE_WAS_UNDEFINED
|
||||||
|
#endif
|
||||||
|
#include "windows.h"
|
||||||
|
|
||||||
|
#ifndef UNICODE_WAS_UNDEFINED
|
||||||
|
#undef UNICODE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
using std::string;
|
||||||
|
using std::wstring;
|
||||||
|
using std::invalid_argument;
|
||||||
|
|
||||||
|
|
||||||
|
class Serial::SerialImpl {
|
||||||
|
public:
|
||||||
|
explicit SerialImpl(const string &port,
|
||||||
|
unsigned long baudrate,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity,
|
||||||
|
stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
virtual ~SerialImpl();
|
||||||
|
|
||||||
|
bool open();
|
||||||
|
|
||||||
|
Serial::SerialPortError getSystemError(int systemErrorCode) const;
|
||||||
|
|
||||||
|
void close();
|
||||||
|
|
||||||
|
bool isOpen() const;
|
||||||
|
|
||||||
|
size_t available();
|
||||||
|
|
||||||
|
bool waitReadable(uint32_t timeout);
|
||||||
|
|
||||||
|
void waitByteTimes(size_t count);
|
||||||
|
|
||||||
|
int waitfordata(size_t data_count, uint32_t timeout, size_t *returned_size);
|
||||||
|
|
||||||
|
size_t read(uint8_t *buf, size_t size = 1);
|
||||||
|
|
||||||
|
size_t write(const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
void flush();
|
||||||
|
|
||||||
|
void flushInput();
|
||||||
|
|
||||||
|
void flushOutput();
|
||||||
|
|
||||||
|
void sendBreak(int duration);
|
||||||
|
|
||||||
|
bool setBreak(bool level);
|
||||||
|
|
||||||
|
bool setRTS(bool level);
|
||||||
|
|
||||||
|
bool setDTR(bool level);
|
||||||
|
|
||||||
|
bool waitForChange();
|
||||||
|
|
||||||
|
bool getCTS();
|
||||||
|
|
||||||
|
bool getDSR();
|
||||||
|
|
||||||
|
bool getRI();
|
||||||
|
|
||||||
|
bool getCD();
|
||||||
|
|
||||||
|
uint32_t getByteTime();
|
||||||
|
|
||||||
|
void setPort(const string &port);
|
||||||
|
|
||||||
|
string getPort() const;
|
||||||
|
|
||||||
|
void setTimeout(Timeout &timeout);
|
||||||
|
|
||||||
|
Timeout getTimeout() const;
|
||||||
|
|
||||||
|
bool setBaudrate(unsigned long baudrate);
|
||||||
|
|
||||||
|
unsigned long getBaudrate() const;
|
||||||
|
|
||||||
|
bool setBytesize(bytesize_t bytesize);
|
||||||
|
|
||||||
|
bytesize_t getBytesize() const;
|
||||||
|
|
||||||
|
bool setParity(parity_t parity);
|
||||||
|
|
||||||
|
parity_t getParity() const;
|
||||||
|
|
||||||
|
bool setStopbits(stopbits_t stopbits);
|
||||||
|
|
||||||
|
stopbits_t getStopbits() const;
|
||||||
|
|
||||||
|
bool setFlowcontrol(flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
flowcontrol_t getFlowcontrol() const;
|
||||||
|
|
||||||
|
|
||||||
|
bool setDcb(DCB *dcb);
|
||||||
|
|
||||||
|
|
||||||
|
bool getDcb(DCB *dcb);
|
||||||
|
|
||||||
|
int readLock();
|
||||||
|
|
||||||
|
int readUnlock();
|
||||||
|
|
||||||
|
int writeLock();
|
||||||
|
|
||||||
|
int writeUnlock();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
bool reconfigurePort();
|
||||||
|
|
||||||
|
public:
|
||||||
|
enum {
|
||||||
|
DEFAULT_RX_BUFFER_SIZE = 2048,
|
||||||
|
DEFAULT_TX_BUFFER_SIZE = 128,
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
wstring port_; // Path to the file descriptor
|
||||||
|
HANDLE fd_;
|
||||||
|
OVERLAPPED _wait_o;
|
||||||
|
|
||||||
|
OVERLAPPED communicationOverlapped;
|
||||||
|
OVERLAPPED readCompletionOverlapped;
|
||||||
|
OVERLAPPED writeCompletionOverlapped;
|
||||||
|
DWORD originalEventMask;
|
||||||
|
DWORD triggeredEventMask;
|
||||||
|
|
||||||
|
COMMTIMEOUTS currentCommTimeouts;
|
||||||
|
COMMTIMEOUTS restoredCommTimeouts;
|
||||||
|
|
||||||
|
bool is_open_;
|
||||||
|
|
||||||
|
Timeout timeout_; // Timeout for read operations
|
||||||
|
unsigned long baudrate_; // Baudrate
|
||||||
|
uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte
|
||||||
|
|
||||||
|
parity_t parity_; // Parity
|
||||||
|
bytesize_t bytesize_; // Size of the bytes
|
||||||
|
stopbits_t stopbits_; // Stop Bits
|
||||||
|
flowcontrol_t flowcontrol_; // Flow Control
|
||||||
|
|
||||||
|
// Mutex used to lock the read functions
|
||||||
|
HANDLE read_mutex;
|
||||||
|
// Mutex used to lock the write functions
|
||||||
|
HANDLE write_mutex;
|
||||||
|
};
|
||||||
|
|
||||||
|
}//serial
|
||||||
|
}//core
|
||||||
|
}//ydlidar
|
||||||
|
|
||||||
|
#endif // SERIAL_IMPL_WINDOWS_H
|
||||||
|
|
||||||
|
#endif // if defined(_WIN32)
|
|
@ -0,0 +1,409 @@
|
||||||
|
#include <algorithm>
|
||||||
|
|
||||||
|
#if !defined(_WIN32) && !defined(__OpenBSD__) && !defined(__FreeBSD__)
|
||||||
|
# include <alloca.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined (__MINGW32__)
|
||||||
|
# define alloca __builtin_alloca
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "serial.h"
|
||||||
|
#include "common.h"
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
using namespace common;
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
using std::min;
|
||||||
|
using std::numeric_limits;
|
||||||
|
using std::vector;
|
||||||
|
using std::size_t;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
using serial::Serial;
|
||||||
|
using serial::bytesize_t;
|
||||||
|
using serial::parity_t;
|
||||||
|
using serial::stopbits_t;
|
||||||
|
using serial::flowcontrol_t;
|
||||||
|
|
||||||
|
class Serial::ScopedReadLock {
|
||||||
|
public:
|
||||||
|
explicit ScopedReadLock(Serial::SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||||
|
this->pimpl_->readLock();
|
||||||
|
}
|
||||||
|
~ScopedReadLock() {
|
||||||
|
this->pimpl_->readUnlock();
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
ScopedReadLock(const ScopedReadLock &);
|
||||||
|
const ScopedReadLock &operator=(ScopedReadLock);
|
||||||
|
|
||||||
|
Serial::SerialImpl *pimpl_;
|
||||||
|
};
|
||||||
|
|
||||||
|
class Serial::ScopedWriteLock {
|
||||||
|
public:
|
||||||
|
explicit ScopedWriteLock(Serial::SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||||
|
this->pimpl_->writeLock();
|
||||||
|
}
|
||||||
|
~ScopedWriteLock() {
|
||||||
|
this->pimpl_->writeUnlock();
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
ScopedWriteLock(const ScopedWriteLock &);
|
||||||
|
const ScopedWriteLock &operator=(ScopedWriteLock);
|
||||||
|
Serial::SerialImpl *pimpl_;
|
||||||
|
};
|
||||||
|
|
||||||
|
Serial::Serial(const string &port, uint32_t baudrate, serial::Timeout timeout,
|
||||||
|
bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol)
|
||||||
|
: pimpl_(new SerialImpl(port, baudrate, bytesize, parity,
|
||||||
|
stopbits, flowcontrol)) {
|
||||||
|
pimpl_->setTimeout(timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::~Serial() {
|
||||||
|
delete pimpl_;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::open() {
|
||||||
|
return pimpl_->open();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::closePort() {
|
||||||
|
pimpl_->close();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::isOpen() {
|
||||||
|
return pimpl_->isOpen();
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::available() {
|
||||||
|
return pimpl_->available();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::waitReadable() {
|
||||||
|
serial::Timeout timeout(pimpl_->getTimeout());
|
||||||
|
return pimpl_->waitReadable(timeout.read_timeout_constant);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::waitByteTimes(size_t count) {
|
||||||
|
pimpl_->waitByteTimes(count);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::SerialPortError Serial::getSystemError(int systemErrorCode) const {
|
||||||
|
return pimpl_->getSystemError(systemErrorCode);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int Serial::waitfordata(size_t data_count, uint32_t timeout,
|
||||||
|
size_t *returned_size) {
|
||||||
|
return pimpl_->waitfordata(data_count, timeout, returned_size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::writeData(const uint8_t *data, size_t size) {
|
||||||
|
return write(data, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::readData(uint8_t *data, size_t size) {
|
||||||
|
return read(data, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *Serial::DescribeError(SerialPortError err) {
|
||||||
|
char const *errorString = "Unknown error";
|
||||||
|
|
||||||
|
switch (err) {
|
||||||
|
case Serial::NoError:
|
||||||
|
errorString = ("No error");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::OpenError:
|
||||||
|
errorString = ("Device is already open");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::NotOpenError:
|
||||||
|
errorString = ("Device is not open");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::TimeoutError:
|
||||||
|
errorString = ("Operation timed out");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::ReadError:
|
||||||
|
errorString = ("Error reading from device");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::WriteError:
|
||||||
|
errorString = ("Error writing to device");
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Serial::ResourceError:
|
||||||
|
errorString = ("Device disappeared from the system");
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// an empty string will be interpreted as "Unknown error"
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return errorString;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
size_t Serial::read_(uint8_t *buffer, size_t size) {
|
||||||
|
return this->pimpl_->read(buffer, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::read(uint8_t *buffer, size_t size) {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
return this->pimpl_->read(buffer, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::read(std::vector<uint8_t> &buffer, size_t size) {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t *>(alloca(size * sizeof(uint8_t)));
|
||||||
|
size_t bytes_read = this->pimpl_->read(buffer_, size);
|
||||||
|
buffer.insert(buffer.end(), buffer_, buffer_ + bytes_read);
|
||||||
|
return bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::read(std::string &buffer, size_t size) {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t *>(alloca(size * sizeof(uint8_t)));
|
||||||
|
size_t bytes_read = this->pimpl_->read(buffer_, size);
|
||||||
|
buffer.append(reinterpret_cast<const char *>(buffer_), bytes_read);
|
||||||
|
return bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
string Serial::readSize(size_t size) {
|
||||||
|
std::string buffer;
|
||||||
|
this->read(buffer, size);
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::readline(string &buffer, size_t size, string eol) {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
size_t eol_len = eol.length();
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t *>(alloca(size * sizeof(uint8_t)));
|
||||||
|
size_t read_so_far = 0;
|
||||||
|
|
||||||
|
while (true) {
|
||||||
|
size_t bytes_read = this->read_(buffer_ + read_so_far, 1);
|
||||||
|
read_so_far += bytes_read;
|
||||||
|
|
||||||
|
if (bytes_read == 0) {
|
||||||
|
break; // Timeout occured on reading 1 byte
|
||||||
|
}
|
||||||
|
|
||||||
|
if (string(reinterpret_cast<const char *>(buffer_ + read_so_far - eol_len),
|
||||||
|
eol_len) == eol) {
|
||||||
|
break; // EOL found
|
||||||
|
}
|
||||||
|
|
||||||
|
if (read_so_far == size) {
|
||||||
|
break; // Reached the maximum read length
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
buffer.append(reinterpret_cast<const char *>(buffer_), read_so_far);
|
||||||
|
return read_so_far;
|
||||||
|
}
|
||||||
|
|
||||||
|
string Serial::readline(size_t size, string eol) {
|
||||||
|
std::string buffer;
|
||||||
|
this->readline(buffer, size, eol);
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string> Serial::readlines(size_t size, string eol) {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
std::vector<std::string> lines;
|
||||||
|
size_t eol_len = eol.length();
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t *>(alloca(size * sizeof(uint8_t)));
|
||||||
|
size_t read_so_far = 0;
|
||||||
|
size_t start_of_line = 0;
|
||||||
|
|
||||||
|
while (read_so_far < size) {
|
||||||
|
size_t bytes_read = this->read_(buffer_ + read_so_far, 1);
|
||||||
|
read_so_far += bytes_read;
|
||||||
|
|
||||||
|
if (bytes_read == 0) {
|
||||||
|
if (start_of_line != read_so_far) {
|
||||||
|
lines.push_back(string(reinterpret_cast<const char *>(buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
}
|
||||||
|
|
||||||
|
break; // Timeout occured on reading 1 byte
|
||||||
|
}
|
||||||
|
|
||||||
|
if (string(reinterpret_cast<const char *>
|
||||||
|
(buffer_ + read_so_far - eol_len), eol_len) == eol) {
|
||||||
|
// EOL found
|
||||||
|
lines.push_back(string(reinterpret_cast<const char *>(buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
start_of_line = read_so_far;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (read_so_far == size) {
|
||||||
|
if (start_of_line != read_so_far) {
|
||||||
|
lines.push_back(string(reinterpret_cast<const char *>(buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
}
|
||||||
|
|
||||||
|
break; // Reached the maximum read length
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return lines;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::write(const string &data) {
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_(reinterpret_cast<const uint8_t *>(data.c_str()),
|
||||||
|
data.length());
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::write(const std::vector<uint8_t> &data) {
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_(&data[0], data.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::write(const uint8_t *data, size_t size) {
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_(data, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t Serial::write_(const uint8_t *data, size_t length) {
|
||||||
|
return pimpl_->write(data, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setPort(const string &port) {
|
||||||
|
ScopedReadLock rlock(this->pimpl_);
|
||||||
|
ScopedWriteLock wlock(this->pimpl_);
|
||||||
|
bool was_open = pimpl_->isOpen();
|
||||||
|
|
||||||
|
if (was_open) {
|
||||||
|
closePort();
|
||||||
|
}
|
||||||
|
|
||||||
|
pimpl_->setPort(port);
|
||||||
|
|
||||||
|
if (was_open) {
|
||||||
|
open();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
string Serial::getPort() const {
|
||||||
|
return pimpl_->getPort();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setTimeout(serial::Timeout &timeout) {
|
||||||
|
pimpl_->setTimeout(timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::Timeout Serial::getTimeout() const {
|
||||||
|
return pimpl_->getTimeout();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setBaudrate(uint32_t baudrate) {
|
||||||
|
return pimpl_->setBaudrate(baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t Serial::getBaudrate() const {
|
||||||
|
return uint32_t(pimpl_->getBaudrate());
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setBytesize(bytesize_t bytesize) {
|
||||||
|
return pimpl_->setBytesize(bytesize);
|
||||||
|
}
|
||||||
|
|
||||||
|
bytesize_t Serial::getBytesize() const {
|
||||||
|
return pimpl_->getBytesize();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setParity(parity_t parity) {
|
||||||
|
return pimpl_->setParity(parity);
|
||||||
|
}
|
||||||
|
|
||||||
|
parity_t Serial::getParity() const {
|
||||||
|
return pimpl_->getParity();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setStopbits(stopbits_t stopbits) {
|
||||||
|
return pimpl_->setStopbits(stopbits);
|
||||||
|
}
|
||||||
|
|
||||||
|
stopbits_t Serial::getStopbits() const {
|
||||||
|
return pimpl_->getStopbits();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setFlowcontrol(flowcontrol_t flowcontrol) {
|
||||||
|
return pimpl_->setFlowcontrol(flowcontrol);
|
||||||
|
}
|
||||||
|
|
||||||
|
flowcontrol_t Serial::getFlowcontrol() const {
|
||||||
|
return pimpl_->getFlowcontrol();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flush() {
|
||||||
|
ScopedReadLock rlock(this->pimpl_);
|
||||||
|
ScopedWriteLock wlock(this->pimpl_);
|
||||||
|
pimpl_->flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flushInput() {
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
pimpl_->flushInput();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flushOutput() {
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
pimpl_->flushOutput();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::sendBreak(int duration) {
|
||||||
|
pimpl_->sendBreak(duration);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setBreak(bool level) {
|
||||||
|
return pimpl_->setBreak(level);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setRTS(bool level) {
|
||||||
|
return pimpl_->setRTS(level);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::setDTR(bool level) {
|
||||||
|
return pimpl_->setDTR(level);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::waitForChange() {
|
||||||
|
return pimpl_->waitForChange();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getCTS() {
|
||||||
|
return pimpl_->getCTS();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getDSR() {
|
||||||
|
return pimpl_->getDSR();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getRI() {
|
||||||
|
return pimpl_->getRI();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getCD() {
|
||||||
|
return pimpl_->getCD();
|
||||||
|
}
|
||||||
|
|
||||||
|
int Serial::getByteTime() {
|
||||||
|
return pimpl_->getByteTime();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,710 @@
|
||||||
|
#ifndef SERIAL_H
|
||||||
|
#define SERIAL_H
|
||||||
|
|
||||||
|
#include <limits>
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
#include <sstream>
|
||||||
|
#include <core/base/v8stdint.h>
|
||||||
|
#include <core/common/ChannelDevice.h>
|
||||||
|
|
||||||
|
namespace ydlidar {
|
||||||
|
namespace core {
|
||||||
|
using namespace common;
|
||||||
|
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible bytesizes for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
fivebits = 5,
|
||||||
|
sixbits = 6,
|
||||||
|
sevenbits = 7,
|
||||||
|
eightbits = 8
|
||||||
|
} bytesize_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible parity types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
parity_none = 0,
|
||||||
|
parity_odd = 1,
|
||||||
|
parity_even = 2,
|
||||||
|
parity_mark = 3,
|
||||||
|
parity_space = 4
|
||||||
|
} parity_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible stopbit types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
stopbits_one = 1,
|
||||||
|
stopbits_two = 2,
|
||||||
|
stopbits_one_point_five
|
||||||
|
} stopbits_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible flowcontrol types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
flowcontrol_none = 0,
|
||||||
|
flowcontrol_software,
|
||||||
|
flowcontrol_hardware
|
||||||
|
} flowcontrol_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Structure for setting the timeout of the serial port, times are
|
||||||
|
* in milliseconds.
|
||||||
|
*
|
||||||
|
* In order to disable the interbyte timeout, set it to Timeout::max().
|
||||||
|
*/
|
||||||
|
struct Timeout {
|
||||||
|
#ifdef max
|
||||||
|
# undef max
|
||||||
|
#endif
|
||||||
|
static uint32_t max() {
|
||||||
|
return std::numeric_limits<uint32_t>::max();
|
||||||
|
}
|
||||||
|
/*!
|
||||||
|
* Convenience function to generate Timeout structs using a
|
||||||
|
* single absolute timeout.
|
||||||
|
*
|
||||||
|
* \param timeout A long that defines the time in milliseconds until a
|
||||||
|
* timeout occurs after a call to read or write is made.
|
||||||
|
*
|
||||||
|
* \return Timeout struct that represents this simple timeout provided.
|
||||||
|
*/
|
||||||
|
static Timeout simpleTimeout(uint32_t timeout) {
|
||||||
|
return Timeout(max(), timeout, 0, timeout, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*! Number of milliseconds between bytes received to timeout on. */
|
||||||
|
uint32_t inter_byte_timeout;
|
||||||
|
/*! A constant number of milliseconds to wait after calling read. */
|
||||||
|
uint32_t read_timeout_constant;
|
||||||
|
/*! A multiplier against the number of requested bytes to wait after
|
||||||
|
* calling read.
|
||||||
|
*/
|
||||||
|
uint32_t read_timeout_multiplier;
|
||||||
|
/*! A constant number of milliseconds to wait after calling write. */
|
||||||
|
uint32_t write_timeout_constant;
|
||||||
|
/*! A multiplier against the number of requested bytes to wait after
|
||||||
|
* calling write.
|
||||||
|
*/
|
||||||
|
uint32_t write_timeout_multiplier;
|
||||||
|
|
||||||
|
explicit Timeout(uint32_t inter_byte_timeout_ = 0,
|
||||||
|
uint32_t read_timeout_constant_ = 0,
|
||||||
|
uint32_t read_timeout_multiplier_ = 0,
|
||||||
|
uint32_t write_timeout_constant_ = 0,
|
||||||
|
uint32_t write_timeout_multiplier_ = 0)
|
||||||
|
: inter_byte_timeout(inter_byte_timeout_),
|
||||||
|
read_timeout_constant(read_timeout_constant_),
|
||||||
|
read_timeout_multiplier(read_timeout_multiplier_),
|
||||||
|
write_timeout_constant(write_timeout_constant_),
|
||||||
|
write_timeout_multiplier(write_timeout_multiplier_) {
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Class that provides a portable serial port interface.
|
||||||
|
*/
|
||||||
|
class Serial : public ChannelDevice {
|
||||||
|
public:
|
||||||
|
|
||||||
|
/// Defines all error codes handled by the CSimpleSocket class.
|
||||||
|
typedef enum {
|
||||||
|
NoError,
|
||||||
|
DeviceNotFoundError,
|
||||||
|
PermissionError,
|
||||||
|
OpenError,
|
||||||
|
ParityError,
|
||||||
|
FramingError,
|
||||||
|
BreakConditionError,
|
||||||
|
WriteError,
|
||||||
|
ReadError,
|
||||||
|
ResourceError,
|
||||||
|
UnsupportedOperationError,
|
||||||
|
UnknownError,
|
||||||
|
TimeoutError,
|
||||||
|
NotOpenError
|
||||||
|
} SerialPortError;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Creates a Serial object and opens the port if a port is specified,
|
||||||
|
* otherwise it remains closed until serial::Serial::open is called.
|
||||||
|
*
|
||||||
|
* \param port A std::string containing the address of the serial port,
|
||||||
|
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||||
|
* on Linux.
|
||||||
|
*
|
||||||
|
* \param baudrate An unsigned 32-bit integer that represents the baudrate
|
||||||
|
*
|
||||||
|
* \param timeout A serial::Timeout struct that defines the timeout
|
||||||
|
* conditions for the serial port. \see serial::Timeout
|
||||||
|
*
|
||||||
|
* \param bytesize Size of each byte in the serial transmission of data,
|
||||||
|
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
|
||||||
|
* eightbits
|
||||||
|
*
|
||||||
|
* \param parity Method of parity, default is parity_none, possible values
|
||||||
|
* are: parity_none, parity_odd, parity_even
|
||||||
|
*
|
||||||
|
* \param stopbits Number of stop bits used, default is stopbits_one,
|
||||||
|
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
|
||||||
|
*
|
||||||
|
* \param flowcontrol Type of flowcontrol used, default is
|
||||||
|
* flowcontrol_none, possible values are: flowcontrol_none,
|
||||||
|
* flowcontrol_software, flowcontrol_hardware
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::IOException
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
explicit Serial(const std::string &port = "",
|
||||||
|
uint32_t baudrate = 9600,
|
||||||
|
Timeout timeout = Timeout(),
|
||||||
|
bytesize_t bytesize = eightbits,
|
||||||
|
parity_t parity = parity_none,
|
||||||
|
stopbits_t stopbits = stopbits_one,
|
||||||
|
flowcontrol_t flowcontrol = flowcontrol_none);
|
||||||
|
|
||||||
|
/*! Destructor */
|
||||||
|
virtual ~Serial();
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Opens the serial port as long as the port is set and the port isn't
|
||||||
|
* already open.
|
||||||
|
*
|
||||||
|
* If the port is provided to the constructor then an explicit call to open
|
||||||
|
* is not needed.
|
||||||
|
*
|
||||||
|
* \see Serial::Serial
|
||||||
|
* \return Returns true if the port is open, false otherwise.
|
||||||
|
*/
|
||||||
|
virtual bool open();
|
||||||
|
|
||||||
|
/*! Gets the open status of the serial port.
|
||||||
|
*
|
||||||
|
* \return Returns true if the port is open, false otherwise.
|
||||||
|
*/
|
||||||
|
virtual bool isOpen();
|
||||||
|
|
||||||
|
/*! Closes the serial port. */
|
||||||
|
virtual void closePort();
|
||||||
|
|
||||||
|
/*! Return the number of characters in the buffer. */
|
||||||
|
virtual size_t available();
|
||||||
|
|
||||||
|
/*! Block until there is serial data to read or read_timeout_constant
|
||||||
|
* number of milliseconds have elapsed. The return value is true when
|
||||||
|
* the function exits with the port in a readable state, false otherwise
|
||||||
|
* (due to timeout or select interruption). */
|
||||||
|
bool waitReadable();
|
||||||
|
|
||||||
|
/*! Block for a period of time corresponding to the transmission time of
|
||||||
|
* count characters at present serial settings. This may be used in con-
|
||||||
|
* junction with waitReadable to read larger blocks of data from the
|
||||||
|
* port. */
|
||||||
|
void waitByteTimes(size_t count);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief getSystemError
|
||||||
|
* @param systemErrorCode
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
Serial::SerialPortError getSystemError(int systemErrorCode = -1) const;
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Block until there is serial data to read or read_timeout_constant
|
||||||
|
* number of milliseconds have elapsed. The return value is greater than zero when
|
||||||
|
* the function exits with the serial port buffer is greater than or
|
||||||
|
* equal to data_count, false otherwise(due to timeout or select interruption).
|
||||||
|
* @param data_count A size_t that indicates how many bytes should be wait from
|
||||||
|
* the given serial port or network buffer.
|
||||||
|
* @param timeout waiting timeout time
|
||||||
|
* @param returned_size if it is not NULL, the actual number of bytes will be returned.
|
||||||
|
* @return A size_t representing the number of bytes wait as a result of the
|
||||||
|
* call to wait.
|
||||||
|
*/
|
||||||
|
virtual int waitfordata(size_t data_count, uint32_t timeout,
|
||||||
|
size_t *returned_size);
|
||||||
|
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \param size A size_t that indicates how many bytes should be written from
|
||||||
|
* the given data buffer.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*/
|
||||||
|
virtual size_t writeData(const uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a given buffer.
|
||||||
|
*
|
||||||
|
* The read function will return in one of three cases:
|
||||||
|
* * The number of requested bytes was read.
|
||||||
|
* * In this case the number of bytes requested will match the size_t
|
||||||
|
* returned by read.
|
||||||
|
* * A timeout occurred, in this case the number of bytes read will not
|
||||||
|
* match the amount requested, but no exception will be thrown. One of
|
||||||
|
* two possible timeouts occurred:
|
||||||
|
* * The inter byte timeout expired, this means that number of
|
||||||
|
* milliseconds elapsed between receiving bytes from the serial port
|
||||||
|
* exceeded the inter byte timeout.
|
||||||
|
* * The total timeout expired, which is calculated by multiplying the
|
||||||
|
* read timeout multiplier by the number of requested bytes and then
|
||||||
|
* added to the read timeout constant. If that total number of
|
||||||
|
* milliseconds elapses after the initial call to read a timeout will
|
||||||
|
* occur.
|
||||||
|
* * An exception occurred, in this case an actual exception will be thrown.
|
||||||
|
*
|
||||||
|
* \param buffer An uint8_t array of at least the requested size.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
virtual size_t readData(uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
/// Returns a human-readable description of the given error code
|
||||||
|
/// or the last error code of a socket
|
||||||
|
static const char *DescribeError(SerialPortError err);
|
||||||
|
|
||||||
|
///
|
||||||
|
/// \brief DescribeError
|
||||||
|
/// \return
|
||||||
|
///
|
||||||
|
virtual const char *DescribeError() {
|
||||||
|
return DescribeError(getSystemError());
|
||||||
|
};
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a given buffer.
|
||||||
|
*
|
||||||
|
* The read function will return in one of three cases:
|
||||||
|
* * The number of requested bytes was read.
|
||||||
|
* * In this case the number of bytes requested will match the size_t
|
||||||
|
* returned by read.
|
||||||
|
* * A timeout occurred, in this case the number of bytes read will not
|
||||||
|
* match the amount requested, but no exception will be thrown. One of
|
||||||
|
* two possible timeouts occurred:
|
||||||
|
* * The inter byte timeout expired, this means that number of
|
||||||
|
* milliseconds elapsed between receiving bytes from the serial port
|
||||||
|
* exceeded the inter byte timeout.
|
||||||
|
* * The total timeout expired, which is calculated by multiplying the
|
||||||
|
* read timeout multiplier by the number of requested bytes and then
|
||||||
|
* added to the read timeout constant. If that total number of
|
||||||
|
* milliseconds elapses after the initial call to read a timeout will
|
||||||
|
* occur.
|
||||||
|
* * An exception occurred, in this case an actual exception will be thrown.
|
||||||
|
*
|
||||||
|
* \param buffer An uint8_t array of at least the requested size.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t read(uint8_t *buffer, size_t size);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a give buffer.
|
||||||
|
*
|
||||||
|
* \param buffer A reference to a std::vector of uint8_t.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t read(std::vector<uint8_t> &buffer, size_t size = 1);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a give buffer.
|
||||||
|
*
|
||||||
|
* \param buffer A reference to a std::string.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t read(std::string &buffer, size_t size = 1);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port and return a string
|
||||||
|
* containing the data.
|
||||||
|
*
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A std::string containing the data read from the port.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
virtual std::string readSize(size_t size = 1);
|
||||||
|
|
||||||
|
/*! Reads in a line or until a given delimiter has been processed.
|
||||||
|
*
|
||||||
|
* Reads from the serial port until a single line has been read.
|
||||||
|
*
|
||||||
|
* \param buffer A std::string reference used to store the data.
|
||||||
|
* \param size A maximum length of a line, defaults to 65536 (2^16)
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t readline(std::string &buffer, size_t size = 65536,
|
||||||
|
std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Reads in a line or until a given delimiter has been processed.
|
||||||
|
*
|
||||||
|
* Reads from the serial port until a single line has been read.
|
||||||
|
*
|
||||||
|
* \param size A maximum length of a line, defaults to 65536 (2^16)
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A std::string containing the line.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
std::string readline(size_t size = 65536, std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Reads in multiple lines until the serial port times out.
|
||||||
|
*
|
||||||
|
* This requires a timeout > 0 before it can be run. It will read until a
|
||||||
|
* timeout occurs and return a list of strings.
|
||||||
|
*
|
||||||
|
* \param size A maximum length of combined lines, defaults to 65536 (2^16)
|
||||||
|
*
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A vector<string> containing the lines.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
std::vector<std::string> readlines(size_t size = 65536, std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \param size A size_t that indicates how many bytes should be written from
|
||||||
|
* the given data buffer.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
* \throw serial::IOException
|
||||||
|
*/
|
||||||
|
size_t write(const uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t write(const std::vector<uint8_t> &data);
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
size_t write(const std::string &data);
|
||||||
|
|
||||||
|
/*! Sets the serial port identifier.
|
||||||
|
*
|
||||||
|
* \param port A const std::string reference containing the address of the
|
||||||
|
* serial port, which would be something like 'COM1' on Windows and
|
||||||
|
* '/dev/ttyS0' on Linux.
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void setPort(const std::string &port);
|
||||||
|
|
||||||
|
/*! Gets the serial port identifier.
|
||||||
|
*
|
||||||
|
* \see Serial::setPort
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
std::string getPort() const;
|
||||||
|
|
||||||
|
/*! Sets the timeout for reads and writes using the Timeout struct.
|
||||||
|
*
|
||||||
|
* There are two timeout conditions described here:
|
||||||
|
* * The inter byte timeout:
|
||||||
|
* * The inter_byte_timeout component of serial::Timeout defines the
|
||||||
|
* maximum amount of time, in milliseconds, between receiving bytes on
|
||||||
|
* the serial port that can pass before a timeout occurs. Setting this
|
||||||
|
* to zero will prevent inter byte timeouts from occurring.
|
||||||
|
* * Total time timeout:
|
||||||
|
* * The constant and multiplier component of this timeout condition,
|
||||||
|
* for both read and write, are defined in serial::Timeout. This
|
||||||
|
* timeout occurs if the total time since the read or write call was
|
||||||
|
* made exceeds the specified time in milliseconds.
|
||||||
|
* * The limit is defined by multiplying the multiplier component by the
|
||||||
|
* number of requested bytes and adding that product to the constant
|
||||||
|
* component. In this way if you want a read call, for example, to
|
||||||
|
* timeout after exactly one second regardless of the number of bytes
|
||||||
|
* you asked for then set the read_timeout_constant component of
|
||||||
|
* serial::Timeout to 1000 and the read_timeout_multiplier to zero.
|
||||||
|
* This timeout condition can be used in conjunction with the inter
|
||||||
|
* byte timeout condition with out any problems, timeout will simply
|
||||||
|
* occur when one of the two timeout conditions is met. This allows
|
||||||
|
* users to have maximum control over the trade-off between
|
||||||
|
* responsiveness and efficiency.
|
||||||
|
*
|
||||||
|
* Read and write functions will return in one of three cases. When the
|
||||||
|
* reading or writing is complete, when a timeout occurs, or when an
|
||||||
|
* exception occurs.
|
||||||
|
*
|
||||||
|
* A timeout of 0 enables non-blocking mode.
|
||||||
|
*
|
||||||
|
* \param timeout A serial::Timeout struct containing the inter byte
|
||||||
|
* timeout, and the read and write timeout constants and multipliers.
|
||||||
|
*
|
||||||
|
* \see serial::Timeout
|
||||||
|
*/
|
||||||
|
void setTimeout(Timeout &timeout);
|
||||||
|
|
||||||
|
/*! Sets the timeout for reads and writes. */
|
||||||
|
void setTimeout(uint32_t inter_byte_timeout, uint32_t read_timeout_constant,
|
||||||
|
uint32_t read_timeout_multiplier, uint32_t write_timeout_constant,
|
||||||
|
uint32_t write_timeout_multiplier) {
|
||||||
|
Timeout timeout(inter_byte_timeout, read_timeout_constant,
|
||||||
|
read_timeout_multiplier, write_timeout_constant,
|
||||||
|
write_timeout_multiplier);
|
||||||
|
return setTimeout(timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*! Gets the timeout for reads in seconds.
|
||||||
|
*
|
||||||
|
* \return A Timeout struct containing the inter_byte_timeout, and read
|
||||||
|
* and write timeout constants and multipliers.
|
||||||
|
*
|
||||||
|
* \see Serial::setTimeout
|
||||||
|
*/
|
||||||
|
Timeout getTimeout() const;
|
||||||
|
|
||||||
|
/*! Sets the baudrate for the serial port.
|
||||||
|
*
|
||||||
|
* Possible baudrates depends on the system but some safe baudrates include:
|
||||||
|
* 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000,
|
||||||
|
* 57600, 115200
|
||||||
|
* Some other baudrates that are supported by some comports:
|
||||||
|
* 128000, 153600, 230400, 256000, 460800, 921600
|
||||||
|
*
|
||||||
|
* \param baudrate An integer that sets the baud rate for the serial port.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
bool setBaudrate(uint32_t baudrate);
|
||||||
|
|
||||||
|
/*! Gets the baudrate for the serial port.
|
||||||
|
*
|
||||||
|
* \return An integer that sets the baud rate for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setBaudrate
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
uint32_t getBaudrate() const;
|
||||||
|
|
||||||
|
/*! Sets the bytesize for the serial port.
|
||||||
|
*
|
||||||
|
* \param bytesize Size of each byte in the serial transmission of data,
|
||||||
|
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
|
||||||
|
* eightbits
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
bool setBytesize(bytesize_t bytesize);
|
||||||
|
|
||||||
|
/*! Gets the bytesize for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setBytesize
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
bytesize_t getBytesize() const;
|
||||||
|
|
||||||
|
/*! Sets the parity for the serial port.
|
||||||
|
*
|
||||||
|
* \param parity Method of parity, default is parity_none, possible values
|
||||||
|
* are: parity_none, parity_odd, parity_even
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
bool setParity(parity_t parity);
|
||||||
|
|
||||||
|
/*! Gets the parity for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setParity
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
parity_t getParity() const;
|
||||||
|
|
||||||
|
/*! Sets the stopbits for the serial port.
|
||||||
|
*
|
||||||
|
* \param stopbits Number of stop bits used, default is stopbits_one,
|
||||||
|
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
bool setStopbits(stopbits_t stopbits);
|
||||||
|
|
||||||
|
/*! Gets the stopbits for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setStopbits
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
stopbits_t getStopbits() const;
|
||||||
|
|
||||||
|
/*! Sets the flow control for the serial port.
|
||||||
|
*
|
||||||
|
* \param flowcontrol Type of flowcontrol used, default is flowcontrol_none,
|
||||||
|
* possible values are: flowcontrol_none, flowcontrol_software,
|
||||||
|
* flowcontrol_hardware
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
bool setFlowcontrol(flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
/*! Gets the flow control for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setFlowcontrol
|
||||||
|
*
|
||||||
|
* \
|
||||||
|
*/
|
||||||
|
flowcontrol_t getFlowcontrol() const;
|
||||||
|
|
||||||
|
/*! Flush the input and output buffers */
|
||||||
|
void flush();
|
||||||
|
|
||||||
|
/*! Flush only the input buffer */
|
||||||
|
void flushInput();
|
||||||
|
|
||||||
|
/*! Flush only the output buffer */
|
||||||
|
void flushOutput();
|
||||||
|
|
||||||
|
/*! Sends the RS-232 break signal. See tcsendbreak(3). */
|
||||||
|
void sendBreak(int duration);
|
||||||
|
|
||||||
|
/*! Set the break condition to a given level. Defaults to true. */
|
||||||
|
bool setBreak(bool level = true);
|
||||||
|
|
||||||
|
/*! Set the RTS handshaking line to the given level. Defaults to true. */
|
||||||
|
bool setRTS(bool level = true);
|
||||||
|
|
||||||
|
/*! Set the DTR handshaking line to the given level. Defaults to true. */
|
||||||
|
virtual bool setDTR(bool level = true);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Blocks until CTS, DSR, RI, CD changes or something interrupts it.
|
||||||
|
*
|
||||||
|
* Can throw an exception if an error occurs while waiting.
|
||||||
|
* You can check the status of CTS, DSR, RI, and CD once this returns.
|
||||||
|
* Uses TIOCMIWAIT via ioctl if available (mostly only on Linux) with a
|
||||||
|
* resolution of less than +-1ms and as good as +-0.2ms. Otherwise a
|
||||||
|
* polling method is used which can give +-2ms.
|
||||||
|
*
|
||||||
|
* \return Returns true if one of the lines changed, false if something else
|
||||||
|
* occurred.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
bool waitForChange();
|
||||||
|
|
||||||
|
/*! Returns the current status of the CTS line. */
|
||||||
|
bool getCTS();
|
||||||
|
|
||||||
|
/*! Returns the current status of the DSR line. */
|
||||||
|
bool getDSR();
|
||||||
|
|
||||||
|
/*! Returns the current status of the RI line. */
|
||||||
|
bool getRI();
|
||||||
|
|
||||||
|
/*! Returns the current status of the CD line. */
|
||||||
|
bool getCD();
|
||||||
|
|
||||||
|
/*! Returns the singal byte time. */
|
||||||
|
virtual int getByteTime();
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
Serial(const Serial &);
|
||||||
|
Serial &operator=(const Serial &);
|
||||||
|
|
||||||
|
// Pimpl idiom, d_pointer
|
||||||
|
class SerialImpl;
|
||||||
|
SerialImpl *pimpl_;
|
||||||
|
SerialPortError m_serialErrno; /// number of last error
|
||||||
|
|
||||||
|
|
||||||
|
// Scoped Lock Classes
|
||||||
|
class ScopedReadLock;
|
||||||
|
class ScopedWriteLock;
|
||||||
|
|
||||||
|
// Read common function
|
||||||
|
size_t read_(uint8_t *buffer, size_t size);
|
||||||
|
// Write common function
|
||||||
|
size_t write_(const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
/// Set internal socket error to that specified error
|
||||||
|
/// @param error type of error
|
||||||
|
void SetSerialPortError(SerialPortError error) {
|
||||||
|
m_serialErrno = error;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Structure that describes a serial device.
|
||||||
|
*/
|
||||||
|
struct PortInfo {
|
||||||
|
|
||||||
|
/*! Address of the serial port (this can be passed to the constructor of Serial). */
|
||||||
|
std::string port;
|
||||||
|
|
||||||
|
/*! Human readable description of serial device if available. */
|
||||||
|
std::string description;
|
||||||
|
|
||||||
|
/*! Hardware ID (e.g. VID:PID of USB serial devices) or "n/a" if not available. */
|
||||||
|
std::string hardware_id;
|
||||||
|
|
||||||
|
/*! Hardware Device ID or "" if not available. */
|
||||||
|
std::string device_id;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Lists the serial ports available on the system
|
||||||
|
*
|
||||||
|
* Returns a vector of available serial ports, each represented
|
||||||
|
* by a serial::PortInfo data structure:
|
||||||
|
*
|
||||||
|
* \return vector of serial::PortInfo.
|
||||||
|
*/
|
||||||
|
std::vector<PortInfo>
|
||||||
|
list_ports();
|
||||||
|
|
||||||
|
} // namespace serial
|
||||||
|
}// namespace core
|
||||||
|
}// namespace ydlidar
|
||||||
|
#endif
|
|
@ -0,0 +1,37 @@
|
||||||
|
#cmake_policy(SET CMP0078 NEW)
|
||||||
|
#cmake_policy(SET CMP0086 OLD)
|
||||||
|
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
||||||
|
add_definitions(-std=c++11) # Use C++11
|
||||||
|
|
||||||
|
#Include directories
|
||||||
|
INCLUDE_DIRECTORIES(
|
||||||
|
${CMAKE_SOURCE_DIR}
|
||||||
|
${CMAKE_SOURCE_DIR}/../
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR}
|
||||||
|
${CMAKE_BINARY_DIR}
|
||||||
|
)
|
||||||
|
SET(MODULE_NAME ydlidar_csharp)
|
||||||
|
|
||||||
|
#################################3
|
||||||
|
add_subdirectory(examples)
|
||||||
|
############################################################################
|
||||||
|
# build ydlidar sdk python version
|
||||||
|
###############################################################################
|
||||||
|
# This is a CMake YDLIDAR SDK for Python
|
||||||
|
INCLUDE(${SWIG_USE_FILE})
|
||||||
|
INCLUDE_DIRECTORIES(${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
SET(CMAKE_SWIG_FLAGS "")
|
||||||
|
#set(CMAKE_SWIG_OUTDIR "${CMAKE_BINARY_DIR}")
|
||||||
|
SET(LIBRARY_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR})
|
||||||
|
set_property(SOURCE ydlidar_sdk.i PROPERTY SWIG_FLAGS "-module" "ydlidar")
|
||||||
|
SET_SOURCE_FILES_PROPERTIES(ydlidar_sdk.i PROPERTIES CPLUSPLUS ON)
|
||||||
|
###############################################################################
|
||||||
|
# This is a CMake YDLIDAR SDK for Python
|
||||||
|
if (${CMAKE_VERSION} VERSION_LESS "3.8.0")
|
||||||
|
swig_add_module(${MODULE_NAME} csharp ydlidar_sdk.i)
|
||||||
|
else()
|
||||||
|
swig_add_library(${MODULE_NAME} LANGUAGE csharp SOURCES ydlidar_sdk.i)
|
||||||
|
endif()
|
||||||
|
SWIG_LINK_LIBRARIES(${MODULE_NAME} ydlidar_sdk)
|
||||||
|
#set_target_properties(${MODULE_NAME} PROPERTIES OUTPUT_NAME "ydlidar")
|
|
@ -0,0 +1,11 @@
|
||||||
|
|
||||||
|
set(curdir ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
FILE(GLOB APP_LIST "${curdir}/*.py")
|
||||||
|
foreach(child ${APP_LIST})
|
||||||
|
install(FILES ${child} DESTINATION bin PERMISSIONS OWNER_READ
|
||||||
|
OWNER_WRITE
|
||||||
|
OWNER_EXECUTE
|
||||||
|
GROUP_EXECUTE
|
||||||
|
WORLD_READ
|
||||||
|
WORLD_EXECUTE)
|
||||||
|
endforeach()
|
|
@ -0,0 +1,45 @@
|
||||||
|
using System;
|
||||||
|
|
||||||
|
namespace LidarTest
|
||||||
|
{
|
||||||
|
class Program
|
||||||
|
{
|
||||||
|
static void Main(string[] args)
|
||||||
|
{
|
||||||
|
ydlidar.os_init();
|
||||||
|
CYdLidar lidarClass = new CYdLidar();
|
||||||
|
string port = "COM7";
|
||||||
|
int optname = (int)LidarProperty.LidarPropSerialPort;
|
||||||
|
lidarClass.setlidaropt(optname, port);
|
||||||
|
optname = (int)LidarProperty.LidarPropSerialBaudrate;
|
||||||
|
lidarClass.setlidaropt(optname, 512000);
|
||||||
|
|
||||||
|
optname = (int)LidarProperty.LidarPropLidarType;
|
||||||
|
|
||||||
|
int lidarType = (int)LidarTypeID.TYPE_TOF;
|
||||||
|
lidarClass.setlidaropt(optname, lidarType);
|
||||||
|
|
||||||
|
|
||||||
|
bool ret = lidarClass.initialize();
|
||||||
|
if(ret)
|
||||||
|
{
|
||||||
|
ret = lidarClass.turnOn();
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
Console.WriteLine("error:" + lidarClass.DescribeError());
|
||||||
|
}
|
||||||
|
LaserScan scan = new LaserScan();
|
||||||
|
while (ret && ydlidar.os_isOk())
|
||||||
|
{
|
||||||
|
if(lidarClass.doProcessSimple(scan))
|
||||||
|
{
|
||||||
|
Console.WriteLine("stamp: "+ scan.stamp + ", size: " + scan.points.Count);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
lidarClass.turnOff();
|
||||||
|
lidarClass.disconnecting();
|
||||||
|
lidarClass.Dispose();
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,63 @@
|
||||||
|
%module ydlidar
|
||||||
|
%include "std_string.i"
|
||||||
|
%include "std_vector.i"
|
||||||
|
%include "std_map.i"
|
||||||
|
%include "typemaps.i"
|
||||||
|
%include "stdint.i"
|
||||||
|
|
||||||
|
%{
|
||||||
|
#define SWIG_FILE_WITH_INIT
|
||||||
|
#define SWIG_PYTHON_EXTRA_NATIVE_CONTAINERS
|
||||||
|
#include "../src/CYdLidar.h"
|
||||||
|
#include "../core/base/typedef.h"
|
||||||
|
#include "../core/common/ydlidar_datatype.h"
|
||||||
|
#include "../core/common/ydlidar_def.h"
|
||||||
|
%}
|
||||||
|
|
||||||
|
%define YDLIDAR_API
|
||||||
|
%enddef
|
||||||
|
|
||||||
|
namespace std {
|
||||||
|
%template(LaserPointVector) vector<LaserPoint>;
|
||||||
|
}
|
||||||
|
|
||||||
|
%extend YDLIDAR_API CYdLidar {
|
||||||
|
public:
|
||||||
|
bool setlidaropt(int optname, int value) {
|
||||||
|
return $self->setlidaropt(optname, (const void *)(&value), sizeof(int));
|
||||||
|
}
|
||||||
|
bool setlidaropt(int optname, float value) {
|
||||||
|
return $self->setlidaropt(optname, (const void *)(&value), sizeof(float));
|
||||||
|
}
|
||||||
|
bool setlidaropt(int optname, bool value) {
|
||||||
|
return $self->setlidaropt(optname, (const void *)(&value), sizeof(bool));
|
||||||
|
}
|
||||||
|
bool setlidaropt(int optname, std::string value) {
|
||||||
|
return $self->setlidaropt(optname, (const void *)(value.c_str()),value.size());
|
||||||
|
}
|
||||||
|
bool getlidaropt_toInt(int optname, int *optval) {
|
||||||
|
return $self->getlidaropt(optname, (void *)(optval),sizeof(int));
|
||||||
|
}
|
||||||
|
bool getlidaropt_toBool(int optname, bool *optval) {
|
||||||
|
return $self->getlidaropt(optname, (void *)(optval),sizeof(bool));
|
||||||
|
}
|
||||||
|
bool getlidaropt_toFloat(int optname, float *optval) {
|
||||||
|
return $self->getlidaropt(optname, (void *)(optval),sizeof(float));
|
||||||
|
}
|
||||||
|
bool getlidaropt_toString(int optname, std::string *optval) {
|
||||||
|
char value[200];
|
||||||
|
bool ret = $self->getlidaropt(optname, (void *)(value),200);
|
||||||
|
*optval = value;
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
%ignore setlidaropt(int optname, const void *optval, int optlen);
|
||||||
|
%ignore getlidaropt(int optname, void *optval, int optlen);
|
||||||
|
|
||||||
|
|
||||||
|
%include "../src/CYdLidar.h"
|
||||||
|
%include "../core/base/typedef.h"
|
||||||
|
%include "../core/common/ydlidar_datatype.h"
|
||||||
|
%include "../core/common/ydlidar_def.h"
|
||||||
|
|
|
@ -0,0 +1,30 @@
|
||||||
|
# YDLIDAR DATASET
|
||||||
|
|LIDAR | Model | Baudrate | SampleRate(K) | Range(m) | Frequency(HZ) | Intenstiy(bit) | SingleChannel | voltage(V)|
|
||||||
|
| :-------- |:--:|:--:|:--:|:--:|:--:|:--:|:--:|:--:|
|
||||||
|
| F4 | 1 | 115200 | 4 | 0.12~12 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| S4 | 4 | 115200 | 4 | 0.10~8.0 | 5~12 (PWM) | false | false | 4.8~5.2 |
|
||||||
|
| S4B | 4/11 | 153600 | 4 | 0.10~8.0 | 5~12(PWM) | true(8) | false | 4.8~5.2 |
|
||||||
|
| S2 | 4/12 | 115200 | 3 | 0.10~8.0 | 4~8(PWM) | false | true | 4.8~5.2 |
|
||||||
|
| G4 | 5 | 230400 | 9/8/4 | 0.28/0.26/0.1~16| 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| X4 | 6 | 128000 | 5 | 0.12~10 | 5~12(PWM) | false | false | 4.8~5.2 |
|
||||||
|
| X2/X2L | 6 | 115200 | 3 | 0.10~8.0 | 4~8(PWM) | false | true | 4.8~5.2 |
|
||||||
|
| G4PRO | 7 | 230400 | 9/8/4 | 0.28/0.26/0.1~16| 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| F4PRO | 8 | 230400 | 4/6 | 0.12~12 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| R2 | 9 | 230400 | 5 | 0.12~16 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G6 | 13 | 512000 | 18/16/8 | 0.28/0.26/0.1~25| 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G2A | 14 | 230400 | 5 | 0.12~12 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G2 | 15 | 230400 | 5 | 0.28~16 | 5~12 | true(8) | false | 4.8~5.2 |
|
||||||
|
| G2C | 16 | 115200 | 4 | 0.1~12 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G4B | 17 | 512000 | 10 | 0.12~16 | 5~12 | true(10) | false | 4.8~5.2 |
|
||||||
|
| G4C | 18 | 115200 | 4 | 0.1~12 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G1 | 19 | 230400 | 9 | 0.28~16 | 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G5 | 20 | 230400 | 9/8/4 | 0.28/0.26/0.1~16| 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| G7 | 21 | 512000 | 18/16/8 | 0.28/0.26/0.1~25| 5~12 | false | false | 4.8~5.2 |
|
||||||
|
| TX8 | 100 | 115200 | 4 | 0.1~8 | 4~8(PWM) | false | true | 4.8~5.2 |
|
||||||
|
| TX20 | 100 | 115200 | 4 | 0.1~20 | 4~8(PWM) | false | true | 4.8~5.2 |
|
||||||
|
| TG15 | 100 | 512000 | 20/18/10 | 0.05~30 | 3~16 | false | false | 4.8~5.2 |
|
||||||
|
| TG30 | 101 | 512000 | 20/18/10 | 0.05~30 | 3~16 | false | false | 4.8~5.2 |
|
||||||
|
| TG50 | 102 | 512000 | 20/18/10 | 0.05~50 | 3~16 | false | false | 4.8~5.2 |
|
||||||
|
| T15 | 200 | 8000 | 20 | 0.05~15 | 5~35 | true | false | 4.8~5.2 |
|
||||||
|
| T30 | 200 | 8000 | 20 | 0.05~30 | 5-35 | true | false | 4.8~5.2 |
|
||||||
|
|
|
@ -0,0 +1,51 @@
|
||||||
|
# FlowChart
|
||||||
|
|
||||||
|
```flow
|
||||||
|
st=>start: Start
|
||||||
|
op=>operation: Set Paramamters and Initialize
|
||||||
|
op1=>operation: TrunOn
|
||||||
|
tr=>operation: Try Again
|
||||||
|
op2=>operation: doProcessSimple
|
||||||
|
op3=>operation: TrunOff
|
||||||
|
op4=>operation: disconnecting
|
||||||
|
cond=>condition: success Yes or No?
|
||||||
|
cond1=>condition: success Yes or No?
|
||||||
|
cond2=>condition: success Yes or No?
|
||||||
|
cond3=>condition: LOOP Yes or No?
|
||||||
|
cond4=>condition: TryAgain Yes or No?
|
||||||
|
e=>end: End
|
||||||
|
en=>end: End
|
||||||
|
|
||||||
|
st(left)->op->cond
|
||||||
|
cond(yes)->op1->cond1
|
||||||
|
cond(no)->op3->op4->e
|
||||||
|
cond1(yes)->op2->cond3
|
||||||
|
cond3(yes)->op2
|
||||||
|
cond3(no, left)->op3->op4->e
|
||||||
|
cond1(no,right)->tr(bottom)->cond4
|
||||||
|
cond4(yes)->op3
|
||||||
|
cond4(no)->op3(right)->op4(right)->e
|
||||||
|
```
|
||||||
|
|
||||||
|
# sequenceDiagram
|
||||||
|
|
||||||
|
```mermaid
|
||||||
|
sequenceDiagram
|
||||||
|
note over UserProgram: Set Paramters
|
||||||
|
note over UserProgram: Initialize SDK
|
||||||
|
UserProgram->Command: Get LiDAR Information
|
||||||
|
Command-->UserProgram: Device connected and Devce Information recevied
|
||||||
|
note over UserProgram: TurnOn
|
||||||
|
UserProgram->Command: Start LiDAR
|
||||||
|
Command-->UserProgram: LiDAR Started successfully
|
||||||
|
UserProgram->LaserScan: Get Laser Scan Data
|
||||||
|
LaserScan-->UserProgram: Laser Scan Data Recvied
|
||||||
|
note over UserProgram: doProcessSimple
|
||||||
|
loop Laser Scan Data
|
||||||
|
LaserScan->UserProgram: doProcessSimple
|
||||||
|
end
|
||||||
|
note over UserProgram: TurnOff
|
||||||
|
UserProgram->Command: TurnOff
|
||||||
|
note over UserProgram: disconnecting
|
||||||
|
UserProgram->Command: disconnecting
|
||||||
|
```
|
|
@ -0,0 +1,32 @@
|
||||||
|
# General FAQs
|
||||||
|
|
||||||
|
## I am new to the YDLIDAR SDK project, where do I start?
|
||||||
|
You have several options:
|
||||||
|
|
||||||
|
- To build YDLidar SDK your computer, start by reviewing the [README.md](https://github.com/YDLIDAR/YDLidar-SDK/blob/master/README.md)
|
||||||
|
|
||||||
|
- To install and build YDLIDAR SDK on a robot Project, go to: [YDLIDAR SDK quick start](https://github.com/YDLIDAR/YDLidar-SDK/blob/master/doc/Tutorials.md).
|
||||||
|
|
||||||
|
---
|
||||||
|
## How do I send a pull request?
|
||||||
|
Sending a pull request is simple.
|
||||||
|
1. Fork the YDLidar-SDK Repository into your GitHub.
|
||||||
|
2. Create a Developer Branch in your Repository.
|
||||||
|
3. Commit your change in your Developer Branch.
|
||||||
|
4. Send the pull request from your GitHub Repository Webpage.
|
||||||
|
|
||||||
|
---
|
||||||
|
## How do I install sdk python API separately?
|
||||||
|
Follow these steps:
|
||||||
|
|
||||||
|
1. install swig:
|
||||||
|
`sudo apt-get install swig`
|
||||||
|
|
||||||
|
2. build sdk:
|
||||||
|
`pyhton setup.py build`
|
||||||
|
|
||||||
|
3. install sdk:
|
||||||
|
`pyhton setup.py install`
|
||||||
|
|
||||||
|
|
||||||
|
**More General FAQs to follow.**
|
|
@ -0,0 +1,10 @@
|
||||||
|
# General FAQs_cn
|
||||||
|
|
||||||
|
## 请问我怎么样使用pull request?
|
||||||
|
使用pull request非常简单。
|
||||||
|
1. 将YDLidar-SDk Repository fork到你自己的Github中。
|
||||||
|
2. 在你的Repository中建立一个开发者 Branch。
|
||||||
|
3. 在开发者Branch中commit你做的任何的改变
|
||||||
|
4. 在你的github网页中使用pull request
|
||||||
|
|
||||||
|
**参考更多的FAQs**
|
|
@ -0,0 +1,8 @@
|
||||||
|
# Hardware FAQs
|
||||||
|
|
||||||
|
---
|
||||||
|
### Which types of YD LiDAR are supported by YDLIDAR-SDK?
|
||||||
|
please visit [this](https://github.com/YDLIDAR/YDLidar-SDK/blob/master/doc/Dataset.md) page.
|
||||||
|
|
||||||
|
---
|
||||||
|
**More Hardware FAQs to follow.**
|
|
@ -0,0 +1,13 @@
|
||||||
|
# 硬件FAQs:
|
||||||
|
### YDLIDAR雷达需要什么硬件支持?
|
||||||
|
* 芯片主频大于30MHz.
|
||||||
|
* 如果芯片主频太低, 数据不能实时解析,数据将会丢失,一些角度范围会丢失,比如:Arduino UNO(16 MHz).
|
||||||
|
* 推荐最小主频大于30MHz才能实时解析雷达数据,如果是TG30这种采样率20K, 需更高的主频.
|
||||||
|
* YDLidar-SDK 不支持控制器芯片,如STM32, Arduino.
|
||||||
|
|
||||||
|
## YDLIDAR雷达可以在什么样的开发板上使用?
|
||||||
|
* 雷达采样率小于6K的,开发板主频大于30MHz就可以.
|
||||||
|
* 更改采样率雷达,开发板主频大于100MHz.
|
||||||
|
|
||||||
|
## YDLidar-SDK支持哪些雷达型号?
|
||||||
|
YDLidar-SDK 支持现有所有EAI标品雷达,定制版本请联系EAI
|
|
@ -0,0 +1,8 @@
|
||||||
|
# FAQs
|
||||||
|
|
||||||
|
- [General FAQs](General_FAQs.md)
|
||||||
|
- [General FAQs cn](General_FAQs_cn.md)
|
||||||
|
- [Hardware FAQs](Hardware_FAQs.md)
|
||||||
|
- [Hardware FAQs cn](Hardware_FAQs_cn.md)
|
||||||
|
- [Software FAQs](Software_FAQs.md)
|
||||||
|
- [Software FAQs cn](Software_FAQs_cn.md)
|
|
@ -0,0 +1,13 @@
|
||||||
|
# Software FAQs
|
||||||
|
|
||||||
|
## Can other operating systems besides Ubuntu and windows be used?
|
||||||
|
|
||||||
|
We have only tested on Ubuntu and windows which means it's the only operating system we currently officially support. Users are always welcome to try different operating systems and can share their patches with the community if they are successfully able to use them.
|
||||||
|
|
||||||
|
---
|
||||||
|
## Can other Languages besides C/C++,Python, C# be used?
|
||||||
|
|
||||||
|
We have only tested on C/C++, Python,C# which means it's the only Languages we currently officially support. Users are always welcome to try different Languages through swig and can share their patches with the community if they are successfully able to use them.
|
||||||
|
|
||||||
|
---
|
||||||
|
**More Software FAQs to follow.**
|
|
@ -0,0 +1,10 @@
|
||||||
|
# 软件FAQ
|
||||||
|
|
||||||
|
## 除了Ubuntu和Windows之外,其他操作系统还能使用吗?
|
||||||
|
|
||||||
|
我们只对Ubuntu和Windows进行了测试,这意味着它是我们目前正式支持的操作系统。欢迎开发者尝试不同的操作系统,如果能够成功地使用它们,可以分享补丁与社区。
|
||||||
|
|
||||||
|
## 除了支持C/C++,Python,C#之外,其他语言还能使用吗?
|
||||||
|
我们只对C/C++,Python,C#进行了测试,这意味着它是我们目前正式支持的语言。欢迎开发者通过SWIG尝试不同的语言,如果能够成功地使用它们,可以分享补丁与社区。
|
||||||
|
|
||||||
|
**更多的软件常见问题。**
|
|
@ -0,0 +1,25 @@
|
||||||
|
# YDLIDAR SDK Documents
|
||||||
|
|
||||||
|
## Quick Start Guide
|
||||||
|
|
||||||
|
[README](quickstart/README.md) - A hardware and software guide to setting up YDLidar-SDK, segregated by versions
|
||||||
|
|
||||||
|
## Communication Protocol
|
||||||
|
|
||||||
|
[YDLIDAR SDK Communication Protocol](YDLidar-SDK-Communication-Protocol.md) - All you need to know about YDLiDAR-SDK Communication Protocol.
|
||||||
|
|
||||||
|
## API
|
||||||
|
|
||||||
|
[YDLIDAR SDK API for Developers](YDLIDAR_SDK_API_for_Developers.md) - All you need to know about YDLiDAR-SDK API
|
||||||
|
|
||||||
|
## Howto Guides
|
||||||
|
|
||||||
|
[README](howto/README.md) - Brief technical solutions to common problems that developers face during the installation and use of the YDLiDAR-SDK
|
||||||
|
|
||||||
|
## Tutorials
|
||||||
|
[Tutorials](Tutorials.md)-Quick Tutorials.
|
||||||
|
|
||||||
|
## FAQs
|
||||||
|
|
||||||
|
[README](FAQs/README.md) - Commonly asked questions about YDLidar-SDK's setup
|
||||||
|
|
Binary file not shown.
|
@ -0,0 +1,25 @@
|
||||||
|
# YDLIDAR SDK Tutorials
|
||||||
|
|
||||||
|
Non-Beginners: If you're already familiar enough with YDLIDAR SDK, you can go through more in-depth SDK tutorial here. However, going over all basic Beginner Level tutorials is still recommended for all users to get exposed to new features.
|
||||||
|
|
||||||
|
If you are new to Linux/windows: You may find it helpful to first do a quick tutorial on common command line tools for linux/windows. A good one is here.
|
||||||
|
|
||||||
|
# Table of Contents
|
||||||
|
- [Beginner Level](#Beginner-level)
|
||||||
|
- [Writing a Simple Lidar Turorial (C++)](#writing-a-simple-lidar-tutorial-(c++))
|
||||||
|
- [Writing a Simple Lidar Network Adapter Turorial (C++)](#writing-a-simple-lidar-network-adapter-tutorial-(c++))
|
||||||
|
- [Writing a Simple Lidar Turorial (Python)](#writing-a-simple-lidar-tutorial-(python))
|
||||||
|
- [Writing a Simple Lidar Turorial (C)](#writing-a-simple-lidar-tutorial-(c))
|
||||||
|
- [Examining the simple lidar tutorial](#examining-the-simple-lidar-tutorial)
|
||||||
|
|
||||||
|
## Beginner Level
|
||||||
|
### [Writing a Simple Lidar Tutorial (C++)](tutorials/writing_lidar_tutorial_c++.md)
|
||||||
|
This tutorial covers how to write a lidar tutorial in C++.
|
||||||
|
### [Writing a Simple Lidar Network Adapter Tutorial (C++)](tutorials/writing_lidar_network_adapter_tutorial_c++.md)
|
||||||
|
This tutorial covers how to write a lidar network adapter tutorial in C++.
|
||||||
|
### [Writing a Simple Lidar Tutorial (Python)](tutorials/writing_lidar_tutorial_python.md)
|
||||||
|
This tutorial covers how to write a lidar tutorial in Python.
|
||||||
|
### [Writing a Simple Lidar Tutorial (C)](tutorials/writing_lidar_tutorial_c.md)
|
||||||
|
This tutorial covers how to write a lidar tutorial in C.
|
||||||
|
### [Examining the simple lidar tutorial](tutorials/examine_the_simple_lidar_tutorial.md)
|
||||||
|
This tutorial examines running the lidar tutorial.
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because one or more lines are too long
|
@ -0,0 +1,346 @@
|
||||||
|
# YDLidar-SDK Communication Protocol
|
||||||
|
## Package Format
|
||||||
|
The response content is the point cloud data scanned by the system. According to the following data format, the data is sent to the external device in hexadecimal to the serial port.
|
||||||
|
No Intensity Byte Offset:
|
||||||
|
![](images/frame.png)
|
||||||
|
|
||||||
|
Intensity Byte Offset:
|
||||||
|
![](images/frame_intensity.png)
|
||||||
|
|
||||||
|
|
||||||
|
Scan data format output by LiDAR:
|
||||||
|
<table>
|
||||||
|
<tr><th>Content <th> Name <th> Description
|
||||||
|
<tr><th>PH(2B) <td> Packet header <td> 2 Byte in length, Fixed at 0x55AA, low is front, high in back.
|
||||||
|
<tr><th>CT(1B) <td> Package type <td> Indicates the current packet type. (0x00 = CT & 0x01): Normal Point cloud packet. (0x01 = CT & 0x01): Zero packet.
|
||||||
|
<tr><th>LSN(1B) <td> Sample Data Number <td> Indicates the number of sampling points contained in the current packet. There is only once zero point of data in thre zero packet. the value is 1.
|
||||||
|
<tr><th>FSA(2B) <td> Starting angle <td> The angle data corresponding to the first sample point in the smapled data.
|
||||||
|
<tr><th>LSA(2B) <td> End angle <td> The angle data corresponding to the last sample point in the sampled data.
|
||||||
|
<tr><th>CS(2B) <td> Check code <td> The check code of the current data packet uses a two-byte exclusive OR to check the current data packet.
|
||||||
|
<tr><th>Si(2B/3B) <td> Sampling data <td> The system test sampling data is the distance data of the sampling point.
|
||||||
|
|
||||||
|
Note: If the LiDAR has intensity, Si is 3 Byte. otherwise is 2 Byte.
|
||||||
|
Si(3B)-->I(1B)(D(2B)): first Byte is Inentsity, The last two bytes are the Distance.
|
||||||
|
</table>
|
||||||
|
|
||||||
|
### Zero resolution
|
||||||
|
Start data packet: (CT & 0x01) = 0x01, LSN = 1, Si = 1.
|
||||||
|
scan frequency: When it was a zero packet, The Lidar Scan frequency: SF = (CT >> 1) / 10.f; The Calculated frequency is the Lidar real-time frequency of the previous frame. If SF is non-zero, the protocol has real-time frequency.
|
||||||
|
For the analysis of the specific values of distance and angle, see the analysis of distance and angle.
|
||||||
|
|
||||||
|
### Distance analysis:
|
||||||
|
+ Distance solution formula:
|
||||||
|
+ Triangle LiDAR:
|
||||||
|
```
|
||||||
|
Distance(i) = Si / 4;
|
||||||
|
```
|
||||||
|
+ TOF LiDAR:
|
||||||
|
```
|
||||||
|
Distance(i) = Si;
|
||||||
|
```
|
||||||
|
|
||||||
|
Si is sampling data. Sampling data is set to E5 6F. Since the system is in the little-endian mode, the
|
||||||
|
sampling point S = 0x6FE5, and it is substituted into the distance solution formula, which yields
|
||||||
|
|
||||||
|
* Triangle LiDAR:
|
||||||
|
```
|
||||||
|
Distance = 7161.25mm
|
||||||
|
```
|
||||||
|
* TOF LiDAR:
|
||||||
|
```
|
||||||
|
Distance = 28645mm
|
||||||
|
```
|
||||||
|
|
||||||
|
### Intensity analysis:
|
||||||
|
Si(3B) split into three bytes : S(0) S(1) S(2)
|
||||||
|
+ Inensity solution formula:
|
||||||
|
+ Triangle LiDAR:
|
||||||
|
```
|
||||||
|
Intensity(i) = uint16_t((S(1) & 0x03)<< 8 | S(0));
|
||||||
|
Distance(i) = uint16_t(S(2) << 8 | S(1)) >> 2;
|
||||||
|
```
|
||||||
|
|
||||||
|
Si is sampling data. Sampling data is set to 1F E5 6F. Since the system is in the little-endian mode, the
|
||||||
|
* Triangle LiDAR:
|
||||||
|
```
|
||||||
|
Intensity = uint16_t((0xE5 & 0x03)<< 8 | 0x1F) = 287;
|
||||||
|
Distance = uint16_t(0x6F << 8 | 0xE5) >> 2 = 7161mm;
|
||||||
|
```
|
||||||
|
### Angle analysis:
|
||||||
|
![](images/angle_q2.png)
|
||||||
|
#### First level analysis:
|
||||||
|
Starting angle solution formula:$$Angle_{FSA}=\frac{Rshiftbit(FSA, 1)}{64}$$
|
||||||
|
End angle solution formula:$$Angle_{LSA}=\frac{Rshiftbit(LSA, 1)}{64}$$
|
||||||
|
Intermediate angle solution formula:
|
||||||
|
$$Angle_{i}=\frac{diff(Angle)}{LSN - 1}*i + Angle_{FSA} (0,1,\ldots,LSN-1)$$
|
||||||
|
$Angle_{0} : Angle_{FSA}$;
|
||||||
|
$Angle_{LSN-1} : Angle_{LSA}$;
|
||||||
|
|
||||||
|
|
||||||
|
`Rshiftbit(data,1)` means shifting the data to the right by one bit.diff Angle means the clockwise angle difference from the starting angle (uncorrected value) to the ending angle (uncorrected value),and LSN represents the number of packet samples in this frame.
|
||||||
|
|
||||||
|
`diff(Angle)`: `(Angle(LSA) - Angle(FSA))` If less than zero, `diff(Angle) = (Angle(LSA)- Angle(FSA)) + 360`, otherwise `diff(Angle) = (Angle(LSA)- Angle(FSA))`
|
||||||
|
|
||||||
|
code
|
||||||
|
```
|
||||||
|
double Angle_FSA = (FSA >> 1) / 64;
|
||||||
|
double Angle_LSA = (LSA >> 1) / 64;
|
||||||
|
double angle_diff = Angle_LSA - Angle_FSA;
|
||||||
|
if(angle_diff < 0) {
|
||||||
|
angle_diff += 360;
|
||||||
|
}
|
||||||
|
double Angle[LSN];
|
||||||
|
for(int i = 0; i < LSN; i++) {
|
||||||
|
if(LSN > 1) {
|
||||||
|
Angle[i] = i* angle_diff / (LSN - 1) + Angle_FSA;
|
||||||
|
} else {
|
||||||
|
Angle[i] = Angle_FSA;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
#### Second-level analysis:
|
||||||
|
Triangle Lidar only has current Second-level analysis, TOF Lidar does not need.
|
||||||
|
|
||||||
|
Angle correction formula: $Angle_{i} = Angle_{i} + AngCorrect_{i}$; ($1,2,\ldots,LSN$)
|
||||||
|
AngCorrect is the angle correction value, and its calculation formula is as follows, $tand^{-1}$ is an inverse trigonometric function. and the return angle value is:
|
||||||
|
|
||||||
|
if($Distance_{i}$ == 0) {
|
||||||
|
$AngCorrect_{i}$ = 0;
|
||||||
|
} else {
|
||||||
|
$AngCorrect_{i} = atan(21.8 * \frac{155.3 - Distance_{i}}{155.3*Distance_{i}}) * (180/3.1415926)$;
|
||||||
|
}
|
||||||
|
|
||||||
|
In the data packet, the 4th to 8th bytes are `28 E5 6F BD 79`, so `LSN = 0x28 = 40(dec)`, `FSA = 0x6FE5`, `LSA = 0x79BD`, and bring in the first-level solution formula, and get:
|
||||||
|
$Angle_{FSA} = 223.78^{°}$
|
||||||
|
$Angle_{LSA} = 243.47^{°}$
|
||||||
|
$diff(Angle) = Angle_{LSA} - Angle_{FSA} = 243.47^{°} - 223.78^{°} = 19.69^{°}$
|
||||||
|
$Angle_{i} = \frac{19.69^{°}}{39}*(i -1) + 223.78^{°}$ ($1,2,\ldots,LSN$)
|
||||||
|
Assume that in the frame data:
|
||||||
|
$Distance_{1} = 1000$
|
||||||
|
$Distance_{LSN} = 8000$
|
||||||
|
bring in the second-level solution formula, you get:
|
||||||
|
$AngCorrect_{1} = -6.7622^{°}$
|
||||||
|
$AngCorrect_{LSN} = -7.8374^{°}$
|
||||||
|
$Angle_{FSA} = Angle_{1} + AngCorrect_{1} = 217.0178^{°}$
|
||||||
|
$Angle_{LSA} = Angle_{LSA} + AngCorrect_{LSA} = 235.6326^{°}$
|
||||||
|
Similarly, $Angle_{i}(2,3, \ldots,LSN-1)$, can be obtained sequentially.
|
||||||
|
|
||||||
|
```
|
||||||
|
for(int i = 0; i < LSN; i++) {
|
||||||
|
if(Distance[i] > 0) {
|
||||||
|
double AngCorrect = atan(21.8 * (155.3 - Distance[i]) / (155.3 * Distance[i]));
|
||||||
|
Angle[i] += AngCorrect * 180 / M_PI;//degree
|
||||||
|
}
|
||||||
|
if(Angle[i] >= 360) {
|
||||||
|
Angle[i] -= 360;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
```
|
||||||
|
Note:
|
||||||
|
* TOF LiDAR does not neeed second-level analysis.
|
||||||
|
|
||||||
|
|
||||||
|
### Check code parsing:
|
||||||
|
The check code uses a two-byte exclusive OR to verify the
|
||||||
|
current data packet. The check code itself does not participate in
|
||||||
|
XOR operations, and the XOR order is not strictly in byte order.
|
||||||
|
The XOR sequence is as shown in the figure. Therefore, the
|
||||||
|
check code solution formula is:
|
||||||
|
|
||||||
|
$$ CS = XOR \sum_{i=1}^{n}(C^i)$$
|
||||||
|
|
||||||
|
CS Sequence
|
||||||
|
<table>
|
||||||
|
<tr><th>PH <th> C(1)
|
||||||
|
<tr><th>FSA <th> C(2)
|
||||||
|
<tr><th>S1 <th> C(3)
|
||||||
|
<tr><th>S2 <th> C(4)
|
||||||
|
<tr><th>... <th> ..
|
||||||
|
<tr><th>Sn <th> C(n-2)
|
||||||
|
<tr><th>[CT | LSN] <th> C(n-1)
|
||||||
|
<tr><th>LSA <th> C(n)
|
||||||
|
</table>
|
||||||
|
|
||||||
|
* Note: XOR(end) indicates the XOR of the element from subscript 1 to end. However, XOR satisfies the exchange law, and the actual solution may not need to follow the XOR sequence.
|
||||||
|
|
||||||
|
### Code
|
||||||
|
No intensity Si(2B):
|
||||||
|
```
|
||||||
|
uint16_t checksumcal = PH;
|
||||||
|
checksumcal ^= FSA;
|
||||||
|
for(int i = 0; i < 2 * LSN; i = i +2 ) {
|
||||||
|
checksumcal ^= uint16_t(data[i+1] <<8 | data[i]);
|
||||||
|
}
|
||||||
|
checksumcal ^= uint16_t(LSN << 8 | CT);
|
||||||
|
checksumcal ^= LSA;
|
||||||
|
|
||||||
|
## uint16_t : unsigned short
|
||||||
|
|
||||||
|
```
|
||||||
|
Intensity Si(3B):
|
||||||
|
```
|
||||||
|
uint16_t checksumcal = PH;
|
||||||
|
checksumcal ^= FSA;
|
||||||
|
for(int i = 0; i < 3 * LSN; i = i + 3) {
|
||||||
|
checksumcal ^= data[i];
|
||||||
|
checksumcal ^= uint16_t(data[i+2] <<8 | data[i + 1]);
|
||||||
|
}
|
||||||
|
checksumcal ^= uint16_t(LSN << 8 | CT);
|
||||||
|
checksumcal ^= LSA;
|
||||||
|
|
||||||
|
## uint16_t : unsigned short
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
### example
|
||||||
|
No Intensity:
|
||||||
|
|
||||||
|
<table>
|
||||||
|
<tr><th>Name <th> Size(Byte) <th> Value <th> Contant <th> Buffer
|
||||||
|
<tr><th rowspan="2" >PH <td rowspan="2" > 2 <td rowspan="2"> 0x55AA <td rowspan="2"> Header <td> 0xAA <tr> <td> 0x55
|
||||||
|
<tr><th>CT <td> 1 <td> 0x01 <td> Type <td> 0x01
|
||||||
|
<tr><th>LSN <td> 1 <td> 0x01 <td> Number <td> 0x01
|
||||||
|
<tr><th rowspan="2" >FSA <td rowspan="2" > 2 <td rowspan="2"> 0xAE53 <td rowspan="2"> Starting Angle <td> 0x53 <tr> <td> 0xAE
|
||||||
|
<tr><th rowspan="2" >LSA <td rowspan="2" > 2 <td rowspan="2"> 0xAE53 <td rowspan="2"> End Andgle <td> 0x53 <tr> <td> 0xAE
|
||||||
|
<tr><th rowspan="2" >CS <td rowspan="2" > 2 <td rowspan="2"> 0x54AB <td rowspan="2"> Check code <td> 0xAB <tr> <td> 0x54
|
||||||
|
<tr><th rowspan="2" >S0 <td rowspan="2" > 2 <td rowspan="2"> 0x0000 <td rowspan="2"> 0 index Distance <td> 0x00 <tr> <td> 0x00
|
||||||
|
</table>
|
||||||
|
|
||||||
|
```
|
||||||
|
uint8_t Buffer[12];
|
||||||
|
Buffer[0] = 0xAA;
|
||||||
|
Buffer[1] = 0x55;
|
||||||
|
Buffer[2] = 0x01;
|
||||||
|
Buffer[3] = 0x01;
|
||||||
|
Buffer[4] = 0x53;
|
||||||
|
Buffer[5] = 0xAE;
|
||||||
|
Buffer[6] = 0x53;
|
||||||
|
Buffer[7] = 0xAE;
|
||||||
|
Buffer[8] = 0xAB;
|
||||||
|
Buffer[9] = 0x54;
|
||||||
|
Buffer[10] = 0x00;
|
||||||
|
Buffer[11] = 0x00;
|
||||||
|
|
||||||
|
uint16_t check_code = 0x55AA;
|
||||||
|
uint8_t CT = Buffer[2] & 0x01;
|
||||||
|
uin8_t LSN = Buffer[3];
|
||||||
|
uint16_t FSA = uint16_t(Buffer[5] << 8 | Buffer[4]);
|
||||||
|
check_code ^= FSA;
|
||||||
|
uint16_t LSA = uint16_t(Buffer[7] << 8 | Buffer[6]);
|
||||||
|
uint16_t CS = uint16_t(Buffer[9] << 8 | Buffer[8]);
|
||||||
|
|
||||||
|
double Distance[LSN];
|
||||||
|
for(int i = 0; i < 2 * LSN; i = i + 2) {
|
||||||
|
uint16_t data = uint16_t(Buffer[10 + i + 1] << 8 | Buffer[10 + i]);
|
||||||
|
check_code ^= data;
|
||||||
|
Distance[i / 2 ] = data / 4;
|
||||||
|
}
|
||||||
|
check_code ^= uint16_t(LSN << 8 | CT);
|
||||||
|
check_code ^= LSA;
|
||||||
|
|
||||||
|
double Angle[LSN];
|
||||||
|
|
||||||
|
if(check_code == CS) {
|
||||||
|
double Angle_FSA = (FSA >> 1) / 64;
|
||||||
|
double Angle_LSA = (LSA >> 1) / 64;
|
||||||
|
double Angle_Diff = (Angle_LSA - Angle_FSA);
|
||||||
|
if(Angle_Diff < 0) {
|
||||||
|
Angle_Diff = Angle_Diff + 360;
|
||||||
|
}
|
||||||
|
for(int i = 0; i < LSN; i++) {
|
||||||
|
if(LSN > 1) {
|
||||||
|
Angle[i] = i * Angle_Diff/ (LSN- 1) + Angle_FSA;
|
||||||
|
} else {
|
||||||
|
Angle[i] = Angle_FSA;
|
||||||
|
}
|
||||||
|
if(Distance[i] > 0) {
|
||||||
|
double AngCorrect = atan(21.8 * (155.3 - Distance[i]) / (155.3 * Distance[i]));
|
||||||
|
Angle[i] = Angle[i] + AngCorrect * 180 / M_PI;
|
||||||
|
}
|
||||||
|
if(Angle[i] >= 360) {
|
||||||
|
Angle[i] -= 360;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
Intensity:
|
||||||
|
|
||||||
|
<table>
|
||||||
|
<tr><th>Name <th> Size(Byte) <th> Value <th> Contant <th> Buffer
|
||||||
|
<tr><th rowspan="2" >PH <td rowspan="2" > 2 <td rowspan="2"> 0x55AA <td rowspan="2"> Header <td> 0xAA <tr> <td> 0x55
|
||||||
|
<tr><th>CT <td> 1 <td> 0x01 <td> Type <td> 0x01
|
||||||
|
<tr><th>LSN <td> 1 <td> 0x01 <td> Number <td> 0x01
|
||||||
|
<tr><th rowspan="2" >FSA <td rowspan="2" > 2 <td rowspan="2"> 0xAE53 <td rowspan="2"> Starting Angle <td> 0x53 <tr> <td> 0xAE
|
||||||
|
<tr><th rowspan="2" >LSA <td rowspan="2" > 2 <td rowspan="2"> 0xAE53 <td rowspan="2"> End Andgle <td> 0x53 <tr> <td> 0xAE
|
||||||
|
<tr><th rowspan="2" >CS <td rowspan="2" > 2 <td rowspan="2"> 0x54AB <td rowspan="2"> Check code <td> 0xAB <tr> <td> 0x54
|
||||||
|
<tr><th>I0 <td> 1 <td> 0x00 <td> 0 index Intensity <td> 0x00
|
||||||
|
<tr><th rowspan="2" >S0 <td rowspan="2" > 2 <td rowspan="2"> 0x0000 <td rowspan="2"> 0 index Distance <td> 0x00 <tr> <td> 0x00
|
||||||
|
</table>
|
||||||
|
|
||||||
|
|
||||||
|
```
|
||||||
|
uint8_t Buffer[13];
|
||||||
|
Buffer[0] = 0xAA;
|
||||||
|
Buffer[1] = 0x55;
|
||||||
|
Buffer[2] = 0x01;
|
||||||
|
Buffer[3] = 0x01;
|
||||||
|
Buffer[4] = 0x53;
|
||||||
|
Buffer[5] = 0xAE;
|
||||||
|
Buffer[6] = 0x53;
|
||||||
|
Buffer[7] = 0xAE;
|
||||||
|
Buffer[8] = 0xAB;
|
||||||
|
Buffer[9] = 0x54;
|
||||||
|
Buffer[10] = 0x00;
|
||||||
|
Buffer[11] = 0x00;
|
||||||
|
Buffer[12] = 0x00;
|
||||||
|
|
||||||
|
uint16_t check_code = 0x55AA;
|
||||||
|
uint8_t CT = Buffer[2] & 0x01;
|
||||||
|
uin8_t LSN = Buffer[3];
|
||||||
|
uint16_t FSA = uint16_t(Buffer[5] << 8 | Buffer[4]);
|
||||||
|
check_code ^= FSA;
|
||||||
|
uint16_t LSA = uint16_t(Buffer[7] << 8 | Buffer[6]);
|
||||||
|
uint16_t CS = uint16_t(Buffer[9] << 8 | Buffer[8]);
|
||||||
|
|
||||||
|
double Distance[LSN];
|
||||||
|
uin16_t Itensity[LSN];
|
||||||
|
for(int i = 0; i < 3 * LSN; i = i + 3) {
|
||||||
|
check_code ^= Buffer[10 + i];
|
||||||
|
uint16_t data = uint16_t(Buffer[10 + i + 2] << 8 | Buffer[10 + i + 1]);
|
||||||
|
check_code ^= data;
|
||||||
|
Itensity[i / 3] = uint16_t((Buffer[10 + i + 1] & 0x03) <<8 | Buffer[10 + i]);
|
||||||
|
Distance[i / 3] = data >> 2;
|
||||||
|
}
|
||||||
|
check_code ^= uint16_t(LSN << 8 | CT);
|
||||||
|
check_code ^= LSA;
|
||||||
|
|
||||||
|
double Angle[LSN];
|
||||||
|
|
||||||
|
if(check_code == CS) {
|
||||||
|
double Angle_FSA = (FSA >> 1) / 64;
|
||||||
|
double Angle_LSA = (LSA >> 1) / 64;
|
||||||
|
double Angle_Diff = (Angle_LSA - Angle_FSA);
|
||||||
|
if(Angle_Diff < 0) {
|
||||||
|
Angle_Diff = Angle_Diff + 360;
|
||||||
|
}
|
||||||
|
for(int i = 0; i < LSN; i++) {
|
||||||
|
if(LSN > 1) {
|
||||||
|
Angle[i] = i * Angle_Diff/ (LSN- 1) + Angle_FSA;
|
||||||
|
} else {
|
||||||
|
Angle[i] = Angle_FSA;
|
||||||
|
}
|
||||||
|
if(Distance[i] > 0) {
|
||||||
|
double AngCorrect = atan(21.8 * (155.3 - Distance[i]) / (155.3 * Distance[i]));
|
||||||
|
Angle[i] = Angle[i] + AngCorrect * 180 / M_PI;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
For more details and usage examples, Refer to [Communication Protocol](https://github.com/YDLIDAR/ydlidar_tutorials/blob/master/CommunicationProtocol/README.md)
|
Binary file not shown.
Binary file not shown.
|
@ -0,0 +1,18 @@
|
||||||
|
# Howto Guides
|
||||||
|
|
||||||
|
## Build
|
||||||
|
- [How to build and install](how_to_build_and_install.md)
|
||||||
|
- [How to build and debug using VSCode](how_to_build_and_debug_using_vscode.md)
|
||||||
|
- [How to create a csharp project](how_to_create_a_csharp_project.md)
|
||||||
|
|
||||||
|
|
||||||
|
## Contribution
|
||||||
|
- [How to create a pull request](how_to_create_a_pull.md)
|
||||||
|
|
||||||
|
## Others
|
||||||
|
- [How to create a udev rules](how_to_create_a_udev_rules.md)
|
||||||
|
|
||||||
|
### Chinese versions
|
||||||
|
|
||||||
|
- [How to install ubuntu](how_to_install_ubuntu_cn.md)
|
||||||
|
- [How to solve slow pull from cn](how_to_solve_slow_pull_from_cn.md)
|
|
@ -0,0 +1,14 @@
|
||||||
|
# How to Build and Debug using VSCode
|
||||||
|
|
||||||
|
Visual Studio Code (hereafter referred to as VSCode) is Microsoft's first lightweight code editor for Linux. Find below a few configuration files that allow the use of VSCode to compile and debug the YDLidar-SDK project. I will elaborate on it below, hoping to bring some help to the developers.
|
||||||
|
|
||||||
|
## Compile the YDLidar-SDK project using VSCode
|
||||||
|
|
||||||
|
You could first set up the YDLidar-SDK project using the [build and release](how_to_build_and_release.md) document under **Build in Visual Studio Code**. Only follow the steps until the `Build the YDLidar-SDK Project in VSCode title`
|
||||||
|
![1](images/vscode/run_tasks.jpg)
|
||||||
|
|
||||||
|
In the pop-up window, select the corresponding The options are as shown below:
|
||||||
|
|
||||||
|
![2](images/vscode/tasks.png)
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,185 @@
|
||||||
|
# How to Build and Install
|
||||||
|
|
||||||
|
* [1. Install CMake](#install-camke)
|
||||||
|
* [2. Build YDLidar-SDK](#build-ydlidar-sdk)
|
||||||
|
* [3. Run Samples](#run-ydlidar-sdk-sample)
|
||||||
|
* [4. Build in VSCode](#build-in-visual-studio-code)
|
||||||
|
|
||||||
|
## Install CMake
|
||||||
|
The installation procedures in Ubuntu 18.04/16.04/14.04 LTS and Windows 7/10 are shown here as examples. For Ubuntu 18.04/16.04/14.04 32-bit LTS and Mac, you can get it in [YDLidar-SDK wiki](https://github.com/YDLIDAR/YDLidar-SDK/wiki).
|
||||||
|
YDLidar SDK requires [CMake 2.8.2+](https://cmake.org/) as dependencies.
|
||||||
|
### Ubuntu 18.04/16.04/14.04 LTS
|
||||||
|
You can install these packages using apt:
|
||||||
|
```shell
|
||||||
|
sudo apt install cmake pkg-config
|
||||||
|
```
|
||||||
|
if you want to use python API, you need to install python and swig(3.0 or higher):
|
||||||
|
```shell
|
||||||
|
sudo apt-get install python swig
|
||||||
|
sudo apt-get install python-pip
|
||||||
|
```
|
||||||
|
### Windows 7/10
|
||||||
|
[vcpkg](https://github.com/Microsoft/vcpkg) is recommended for building the dependency libraries as follows:
|
||||||
|
For the 32-bit project:
|
||||||
|
```
|
||||||
|
.\vcpkg install cmake
|
||||||
|
.\vcpkg integrate install
|
||||||
|
```
|
||||||
|
For the 64-bit project:
|
||||||
|
```
|
||||||
|
.\vcpkg install cmake:x64-windows
|
||||||
|
.\vcpkg integrate install
|
||||||
|
```
|
||||||
|
if you want to use python API, you need to install python and swig:
|
||||||
|
[python office install](https://wiki.python.org/moin/BeginnersGuide/Download)
|
||||||
|
[swig office install](http://www.swig.org/download.html)
|
||||||
|
|
||||||
|
## Build YDLidar-SDK
|
||||||
|
### Ubuntu 18.04/16.04/14.04 LTS
|
||||||
|
In the YDLidar SDK directory, run the following commands to compile the project:
|
||||||
|
```
|
||||||
|
git clone https://github.com/YDLIDAR/YDLidar-SDK.git
|
||||||
|
cd YDLidar-SDK/build
|
||||||
|
cmake ..
|
||||||
|
make
|
||||||
|
sudo make install
|
||||||
|
```
|
||||||
|
Note:
|
||||||
|
If already installed python and swig, `sudo make install` command will also install python API without the following operations.
|
||||||
|
|
||||||
|
### python API install separtately:
|
||||||
|
The Next operation only installs the python API, if the above command has been executed, there is no need to perform the next operation.
|
||||||
|
```
|
||||||
|
cd YDLidar-SDK
|
||||||
|
pip install .
|
||||||
|
|
||||||
|
# Another method
|
||||||
|
python setup.py build
|
||||||
|
python setup.py install
|
||||||
|
```
|
||||||
|
|
||||||
|
### Windows 7/10
|
||||||
|
Then, in the YDLidar SDK directory, run the following commands to create the Visual Studio solution file. Please replace [vcpkgroot] with your vcpkg installation path.
|
||||||
|
Generate the 32-bit project:
|
||||||
|
```
|
||||||
|
cd build && \
|
||||||
|
cmake .. "-DCMAKE_TOOLCHAIN_FILE=[vcpkgroot]\scripts\buildsystems\vcpkg.cmake"
|
||||||
|
```
|
||||||
|
Generate the 64-bit project:
|
||||||
|
```
|
||||||
|
cd build && \
|
||||||
|
cmake .. -G "Visual Studio 15 2017 Win64" "-DCMAKE_TOOLCHAIN_FILE=[vcpkgroot]\scripts\buildsystems\vcpkg.cmake"
|
||||||
|
```
|
||||||
|
Note:
|
||||||
|
* For build C# API, set BUILD_CSHARP option to ON.
|
||||||
|
* You need to install [Swig](http://www.swig.org/download.html), When building C# API.
|
||||||
|
eg:
|
||||||
|
```
|
||||||
|
cmake -DBUILD_CSHARP=ON .. -G "Visual Studio 15 2017 Win64" "-DCMAKE_TOOLCHAIN_FILE=[vcpkgroot]\scripts\buildsystems\vcpkg.cmake"
|
||||||
|
```
|
||||||
|
|
||||||
|
#### Compile YDLidar SDK
|
||||||
|
You can now compile the YDLidar SDK in Visual Studio.
|
||||||
|
Note:
|
||||||
|
* For more windows build and Run, Please refer to [How to gerenrate Vs Project by CMake](how_to_gerenrate_vs_project_by_cmake.md)
|
||||||
|
* For VS2017 or higher, Please refer to [CMake projects in visual studio](https://docs.microsoft.com/zh-cn/cpp/build/cmake-projects-in-visual-studio?view=vs-2019)
|
||||||
|
|
||||||
|
### Packaging Project
|
||||||
|
```
|
||||||
|
cpack
|
||||||
|
```
|
||||||
|
![](images/cpack.png)
|
||||||
|
|
||||||
|
## Run YDLidar SDK Sample
|
||||||
|
Three samples are provided in samples, which demonstrate how to configure YDLidar LiDAR units and receive the laser scan data when directly connecting YDLidar SDK to LiDAR units or by using a YDLidar Adapter board, respectively. The sequence diagram is shown as below:
|
||||||
|
|
||||||
|
![](images/sequence.png)
|
||||||
|
|
||||||
|
### Ubuntu 18.04/16.04 /14.04 LTS
|
||||||
|
For Ubuntun 18.04/16.04/14.04 LTS, run the *ydlidar_test* if connect with the Triangle LiDAR unit(s) or TOF LiDAR unit(s):
|
||||||
|
```
|
||||||
|
./ydlidar_test
|
||||||
|
```
|
||||||
|
### Windows 7/10
|
||||||
|
After compiling the YDLidar SDK as shown in section 4.1.2, you can find `ydlidar_test.exe` in the {YDLidar-SDK}\build\Debug or {YDLidar-SDK}\build\Release folder, respectively, which can be run directly.
|
||||||
|
|
||||||
|
Then you can see SDK initializing the information as below:
|
||||||
|
|
||||||
|
![](images/sdk_init.png)
|
||||||
|
|
||||||
|
Then you can see SDK Scanning the information as below:
|
||||||
|
|
||||||
|
![](images/sdk_scanning.png)
|
||||||
|
|
||||||
|
### Connect to the specific LiDAR units
|
||||||
|
|
||||||
|
Samples we provided will connect all the LiDAR device in you USB in default.There are two ways to connect the specific units:
|
||||||
|
|
||||||
|
* run sample with input options in serial port.
|
||||||
|
|
||||||
|
* run sample with input options in network.
|
||||||
|
|
||||||
|
#### Program Options
|
||||||
|
|
||||||
|
We provide the following program options for connecting the specific units :
|
||||||
|
```
|
||||||
|
[Please select the lidar baudrate:]: input LiDAR BaudRate.
|
||||||
|
[Whether the Lidar is one-way communication[yes/no]:]: Whether The Current LiDAR is single-channel.
|
||||||
|
[Please enter the lidar scan frequency[5-12]:]:input LiDAR Scan Frequency.
|
||||||
|
```
|
||||||
|
|
||||||
|
Here is the example:
|
||||||
|
```
|
||||||
|
__ ______ _ ___ ____ _ ____
|
||||||
|
\ \ / / _ \| | |_ _| _ \ / \ | _ \
|
||||||
|
\ V /| | | | | | || | | |/ _ \ | |_) |
|
||||||
|
| | | |_| | |___ | || |_| / ___ \| _ <
|
||||||
|
|_| |____/|_____|___|____/_/ \_\_| \_\
|
||||||
|
|
||||||
|
Baudrate:
|
||||||
|
0. 115200
|
||||||
|
1. 128000
|
||||||
|
2. 153600
|
||||||
|
3. 230400
|
||||||
|
4. 512000
|
||||||
|
Please select the lidar baudrate:4
|
||||||
|
Whether the Lidar is one-way communication[yes/no]:no
|
||||||
|
Please enter the lidar scan frequency[5-12]:10
|
||||||
|
```
|
||||||
|
|
||||||
|
### Python Run
|
||||||
|
```
|
||||||
|
cd python/examples
|
||||||
|
# Console
|
||||||
|
python tof_test.py
|
||||||
|
# If it's a drawing
|
||||||
|
pip install numpy
|
||||||
|
pip install matplotlib
|
||||||
|
python plot_tof_test.py
|
||||||
|
```
|
||||||
|
![](images/ydlidar_lidar_monitor.png)
|
||||||
|
|
||||||
|
|
||||||
|
## Build in Visual Studio Code
|
||||||
|
### Install VSCode
|
||||||
|
The easiest way to install for Debian/Ubuntu based distributions is to download from https://code.visualstudio.com and install the .deb package (64-bit) either through the graphical software center if it's available or through the command line with:
|
||||||
|
```bash
|
||||||
|
sudo dpkg -i <file>.deb
|
||||||
|
sudo apt-get install -f # Install dependencies
|
||||||
|
```
|
||||||
|
### Start VSCode
|
||||||
|
Start VSCode with the following command:
|
||||||
|
```bash
|
||||||
|
code
|
||||||
|
```
|
||||||
|
### Open the YDLidar-SDK project in VSCode
|
||||||
|
Use the keyboard shortcut **(Ctrl+K Ctrl+O)** to open the YDLidar-SDK project.
|
||||||
|
### Build the YDLidar-SDK project in VSCode
|
||||||
|
Use the keyboard shortcut **(Ctrl+Shift+B)** to build the YDLidar-SDK project.
|
||||||
|
### Run all unit tests for the YDLidar-SDK project in VSCode
|
||||||
|
Select the "Tasks->Run Tasks..." menu command and click "run all unit tests for the YDLidar-SDK project" from a popup menu to check the code style for the YDLidar-SDK project.
|
||||||
|
|
||||||
|
### Run a code style check task for the YDLidar-SDK project in VSCode
|
||||||
|
Select the "Tasks->Run Tasks..." menu command and click "code style check for the YDLidar-SDK project" from a popup menu to check the code style for the YDLidar-SDK project.
|
||||||
|
### Clean the YDLidar-SDK project in VSCode
|
||||||
|
Select the "Tasks->Run Tasks..." menu command and click "clean the YDLidar-SDK project" from a popup menu to clean the YDLidar-SDK project.
|
|
@ -0,0 +1,35 @@
|
||||||
|
# How to create a csharp project
|
||||||
|
|
||||||
|
You can follow a sample setup:
|
||||||
|
|
||||||
|
- You need to install [Swig](http://www.swig.org/download.html).
|
||||||
|
- Set BUILD_CSHARP option to ON
|
||||||
|
|
||||||
|
```
|
||||||
|
cmake -DBUILD_CSHARP=ON .. -G "Visual Studio 15 2017 Win64" "-DCMAKE_TOOLCHAIN_FILE=[vcpkgroot]\scripts\buildsystems\vcpkg.cmake"
|
||||||
|
```
|
||||||
|
|
||||||
|
- Compiling the SDK will generate the CSharp interface file and `ydlidar_csharp.dll` library
|
||||||
|
|
||||||
|
![0](images/csharp_build.png)
|
||||||
|
|
||||||
|
|
||||||
|
- Copy all `*.cs` files generated by the YDLidar-SDK to your project
|
||||||
|
|
||||||
|
![1](images/csharp_project.png)
|
||||||
|
|
||||||
|
|
||||||
|
- If the following error occurs, you need to copy the compiled `ydlidar_csharp.dll` to the binary directory
|
||||||
|
|
||||||
|
![2](images/csharp_exception.png)
|
||||||
|
|
||||||
|
|
||||||
|
- Copy `ydlidar_csharp.dll` to your project Binary directory
|
||||||
|
|
||||||
|
![2](images/csharp_library.png)
|
||||||
|
|
||||||
|
|
||||||
|
- Set up lidar test for TG30
|
||||||
|
|
||||||
|
![2](images/csharp_running.png)
|
||||||
|
|
|
@ -0,0 +1,53 @@
|
||||||
|
# How to create a pull request
|
||||||
|
|
||||||
|
You can follow the standard [github approach](https://help.github.com/articles/using-pull-requests/) to contribute code to YDLidar-SDK. Here is a sample setup:
|
||||||
|
|
||||||
|
- Fork a new repo with your GitHub username.
|
||||||
|
- Set up your GitHub personal email and user name
|
||||||
|
|
||||||
|
```
|
||||||
|
git config user.name "XXX"
|
||||||
|
git config user.email "XXX@[XXX.com]"
|
||||||
|
```
|
||||||
|
|
||||||
|
- Clone your fork (Please replace "USERNAME" with your GitHub user name.)
|
||||||
|
|
||||||
|
```
|
||||||
|
(Use SSH) git clone git@github.com:USERNAME/YDLidar-SDK.git
|
||||||
|
(Use HTTPS) git clone https://github.com/USERNAME/YDLidar-SDK.git
|
||||||
|
```
|
||||||
|
|
||||||
|
- Add YDLidar-SDK repository as upstream
|
||||||
|
|
||||||
|
```
|
||||||
|
(Use SSH) git remote add upstream git@github.com:YDLIDAR/YDLidar-SDK.git
|
||||||
|
(Use HTTPS) git remote add upstream https://github.com/YDLIDAR/YDLidar-SDK.git
|
||||||
|
```
|
||||||
|
|
||||||
|
- Confirm that the upstream branch has been added
|
||||||
|
```
|
||||||
|
git remote -v
|
||||||
|
```
|
||||||
|
|
||||||
|
- Create a new branch, make changes and commit
|
||||||
|
|
||||||
|
```
|
||||||
|
git checkout -b "my_dev"
|
||||||
|
```
|
||||||
|
|
||||||
|
- Sync up with the YDLIDAR/YDLidar-SDK repo
|
||||||
|
|
||||||
|
```
|
||||||
|
git pull --rebase upstream master
|
||||||
|
```
|
||||||
|
|
||||||
|
- Push local developments to your own forked repository
|
||||||
|
|
||||||
|
```
|
||||||
|
git push -f -u origin "my_dev"
|
||||||
|
```
|
||||||
|
|
||||||
|
- Generate a new pull request between "YDLIDAR/YDLidar-SDK:master" and "forked repo:my_dev"
|
||||||
|
- Collaborators will review and merge the commit (this may take some time, please be patient)
|
||||||
|
|
||||||
|
Thanks a lot for your contributions!
|
|
@ -0,0 +1,64 @@
|
||||||
|
# How to create a udev rules
|
||||||
|
|
||||||
|
- [Introduction](#introduction)
|
||||||
|
- [Create The New UDEV Rules](#create-the-new-udev-rules)
|
||||||
|
- [Create new udev file](#create-new-udev-file)
|
||||||
|
- [Query serial port number through udevadm ](#query-serial-port-number-through-udevadm)
|
||||||
|
- [Create UDEV Permission Rule For tty Devices](#create-udev-permission-rule-for-tty-devices)
|
||||||
|
- [Restart The UDEV Service](#restart-the-udev-service)
|
||||||
|
|
||||||
|
|
||||||
|
## Introduction
|
||||||
|
The serial port is used under Linux. The serial port number will change with the insertion order of multiple serial ports. This problem can be solved by setting the serial port alias.
|
||||||
|
|
||||||
|
## Create The New UDEV Rules
|
||||||
|
Create a new `ydlidar_ports.rules` file and write the corresponding serial port rules to the file.
|
||||||
|
|
||||||
|
### Create new udev file
|
||||||
|
```shell
|
||||||
|
sudo gedit /etc/udev/rules.d/ydlidar_ports.rules
|
||||||
|
```
|
||||||
|
or
|
||||||
|
```shell
|
||||||
|
sudo vim /etc/udev/rules.d/ydlidar_ports.rules
|
||||||
|
```
|
||||||
|
### Query serial port number through udevadm
|
||||||
|
```shell
|
||||||
|
udevadm info -a -n /dev/ttyUSB0 | grep KERNELS
|
||||||
|
```
|
||||||
|
result as follows:
|
||||||
|
![](images/ttyUSB0.png)
|
||||||
|
|
||||||
|
```shell
|
||||||
|
udevadm info -a -n /dev/ttyUSB1 | grep KERNELS
|
||||||
|
```
|
||||||
|
result as follows:
|
||||||
|
![](images/ttyUSB1.png)
|
||||||
|
|
||||||
|
### Create UDEV Permission Rule For tty Devices
|
||||||
|
Write the first KERNELS queried above into the new `ydlidar_ports.rules` file. Add these two following rules in it.
|
||||||
|
```ydlidar_ports.rules
|
||||||
|
SUBSYSTEM=="tty", KERNELS=="1-1:1.0", SYMLINK+="ydlidar", MODE="0666", GROUP:="dialout"
|
||||||
|
SUBSYSTEM=="tty", KERNELS=="1-2:1.0", SYMLINK+="ydlidar1", MODE="0666", GROUP:="dialout"
|
||||||
|
```
|
||||||
|
|
||||||
|
## Restart The UDEV Service
|
||||||
|
Save the file and close it. Then as root, tell systemd-udevd to reload the rules files (this also reloads other databases such as the kernel module index), by running.
|
||||||
|
```shell
|
||||||
|
sudo udevadm control --reload
|
||||||
|
```
|
||||||
|
and
|
||||||
|
```shell
|
||||||
|
sudo service udev reload
|
||||||
|
sudo service udev restart
|
||||||
|
```
|
||||||
|
Note: If it doesn't work, plug and unplug the USB or restart the computer
|
||||||
|
|
||||||
|
### You can query the corresponding results with the following command
|
||||||
|
```shell
|
||||||
|
ls -l /dev/ydlidar*
|
||||||
|
|
||||||
|
lrwxrwxrwx 1 root dialout 7 Feb 17 13:27 /dev/ydlidar -> ttyUSB0
|
||||||
|
lrwxrwxrwx 1 root dialout 7 Feb 17 13:27 /dev/ydlidar1 -> ttyUSB1
|
||||||
|
|
||||||
|
```
|
|
@ -0,0 +1,17 @@
|
||||||
|
# Introduction
|
||||||
|
|
||||||
|
The Visual Studio version recommended by YDLidar-SDK to use is Visual Studio 2017. This document decribes steps to run YDLidar-SDK on Visual Studio 2017.
|
||||||
|
|
||||||
|
The YDLidar-SDK version used in this document is the lastest release version which is 1.0.0. And this document focuses on How to Install Software, and conforms to the steps and rules provided by YDLidar-SDK.
|
||||||
|
|
||||||
|
# Download YDLidar-SDK
|
||||||
|
|
||||||
|
please refer to [YDLidar-SDK Software Installation](https://github.com/YDLIDAR/YDLidar-SDK/blob/master/docs/quickstart/ydlidar_sdk_software_installation_guide.md),download YDLidar-SDK version 1.0.0 source code onto the computer.
|
||||||
|
|
||||||
|
# Install CMake
|
||||||
|
|
||||||
|
Please follow the [official guide to install the cmake](https://cmake.org/install).
|
||||||
|
|
||||||
|
|
||||||
|
# Build and Run YDLIDAR SDK
|
||||||
|
Please refer to [How to build and release](https://github.com/YDLIDAR/YDLidar-SDK/blob/master/doc/howto/how_to_build_and_release.md).
|
|
@ -0,0 +1,39 @@
|
||||||
|
# Github访问慢解决方案
|
||||||
|
|
||||||
|
浏览器打开如下网站
|
||||||
|
|
||||||
|
http://github.global.ssl.fastly.net.ipaddress.com/
|
||||||
|
|
||||||
|
找到对应IP地址,例如:151.101.xx.xx
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
浏览器打开另外一个网站
|
||||||
|
|
||||||
|
http://github.com.ipaddress.com/
|
||||||
|
|
||||||
|
找到对应IP地址。例如:192.30.xx.xx
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
编辑hosts文件
|
||||||
|
|
||||||
|
```
|
||||||
|
sudo vim /etc/hosts
|
||||||
|
```
|
||||||
|
|
||||||
|
在文件中加入如下两行
|
||||||
|
|
||||||
|
```
|
||||||
|
192.30.xx.xx github.com
|
||||||
|
151.101.xx.xx github.global.ssl.fastly.net
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
如果使用mac,还需更新DNS缓存
|
||||||
|
|
||||||
|
```
|
||||||
|
sudo dscacheutil -flushcache
|
||||||
|
```
|
||||||
|
|
Binary file not shown.
After Width: | Height: | Size: 78 KiB |
Binary file not shown.
After Width: | Height: | Size: 55 KiB |
Binary file not shown.
After Width: | Height: | Size: 96 KiB |
Binary file not shown.
After Width: | Height: | Size: 35 KiB |
Binary file not shown.
After Width: | Height: | Size: 51 KiB |
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue