From 6aece8be6b5b8f0c9b326846241aac11134d8f2b Mon Sep 17 00:00:00 2001 From: DavidHu Date: Mon, 19 Sep 2022 21:10:05 +0800 Subject: [PATCH] =?UTF-8?q?[update]=E7=89=88=E6=9C=AC=E5=8F=B7v2.3.5?= =?UTF-8?q?=EF=BC=8C1.=20=E5=BC=80=E5=8F=91=E8=80=85=E7=9A=84PR=EF=BC=9A?= =?UTF-8?q?=20Organize=20the=20package=20config=20and=20clarify=20the=20li?= =?UTF-8?q?cense=20#1=20=EF=BC=9B=202.=20=E4=BF=AE=E6=94=B9ROS=20laser=20s?= =?UTF-8?q?can=E6=B6=88=E6=81=AF=E7=9A=84angle=5Fincrement=E8=AE=A1?= =?UTF-8?q?=E7=AE=97=E6=96=B9=E5=BC=8F=EF=BC=9B=203.=20=E6=9B=B4=E6=96=B0R?= =?UTF-8?q?EADME?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- CMakeLists.txt | 13 +++++++++ README.md | 50 ++++++++++++++++---------------- launch/ld06.launch | 14 ++++++--- launch/ld19.launch | 14 ++++++--- ldlidar_driver/lipkg.cpp | 2 +- package.xml | 34 +++++++++++++++------- {scripts => rules}/ldlidar.rules | 0 scripts/create_udev_rules.sh | 2 +- scripts/delete_udev_rules.sh | 2 +- src/publish_node/main.cpp | 28 +++++++++++------- 10 files changed, 102 insertions(+), 57 deletions(-) rename {scripts => rules}/ldlidar.rules (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3d544d6..d01fd7d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -195,6 +195,11 @@ target_link_libraries(${PROJECT_NAME}_listen_node ${catkin_LIBRARIES}) # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) +install(PROGRAMS + scripts/create_udev_rules.sh + scripts/delete_udev_rules.sh + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) ## Mark executables and/or libraries for installation # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node @@ -202,6 +207,11 @@ target_link_libraries(${PROJECT_NAME}_listen_node ${catkin_LIBRARIES}) # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) +install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}_listen_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ @@ -216,6 +226,9 @@ target_link_libraries(${PROJECT_NAME}_listen_node ${catkin_LIBRARIES}) # # myfile2 # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) +install(DIRECTORY launch rules rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) ############# ## Testing ## diff --git a/README.md b/README.md index 8ab8fda..97154a9 100644 --- a/README.md +++ b/README.md @@ -31,13 +31,19 @@ sudo chmod 777 /dev/ttyUSB0 - 第三步,修改`launch/`目录下雷达产品型号对应的lanuch文件中的`port_name`值,以ld06.launch为例,如下所示. ```xml + + + + + + - - - + + + @@ -53,12 +59,12 @@ sudo chmod 777 /dev/ttyUSB0 - + - + ``` ## 2. 编译方法 @@ -129,13 +135,6 @@ catkin_make ```bash rviz ``` - -| 产品型号: | Fixed Frame: | Topic: | -| ------------------ | ------------ | ------------- | -| LDROBOT LiDAR LD06 | base_laser | /scan | -| LDROBOT LiDAR LD19 | base_laser | /scan | - - # Instructions > This SDK is only applicable to the LiDAR products sold by Shenzhen LDROBOT Co., LTD. The product models are : @@ -168,13 +167,19 @@ sudo chmod 777 /dev/ttyUSB0 - Modify the `port_name` value in the Lanuch file corresponding to the radar product model under `launch/`, using `ld06.launch` as an example, as shown below. ``` xml + + + + + + - - - + + + @@ -190,12 +195,12 @@ sudo chmod 777 /dev/ttyUSB0 - + - + ``` ## step 2: build @@ -266,9 +271,4 @@ catkin_make - new a terminal (Ctrl + Alt + T) and use Rviz tool,open the rviz config file below the rviz folder of the readme file directory ```bash rviz -``` - -| Product: | Fixed Frame: | Topic: | -| ------------------ | ------------ | ------------- | -| LDROBOT LiDAR LD06 | base_laser | /scan | -| LDROBOT LiDAR LD19 | base_laser | /scan | \ No newline at end of file +``` \ No newline at end of file diff --git a/launch/ld06.launch b/launch/ld06.launch index d097b0b..7821b05 100644 --- a/launch/ld06.launch +++ b/launch/ld06.launch @@ -1,10 +1,16 @@ + + + + + + - - - + + + @@ -25,5 +31,5 @@ - + \ No newline at end of file diff --git a/launch/ld19.launch b/launch/ld19.launch index 9ca5b0d..133d7c7 100644 --- a/launch/ld19.launch +++ b/launch/ld19.launch @@ -1,10 +1,16 @@ + + + + + + - - - + + + @@ -25,5 +31,5 @@ - + \ No newline at end of file diff --git a/ldlidar_driver/lipkg.cpp b/ldlidar_driver/lipkg.cpp index 9a20a22..392ba01 100644 --- a/ldlidar_driver/lipkg.cpp +++ b/ldlidar_driver/lipkg.cpp @@ -57,7 +57,7 @@ uint8_t CalCRC8(const uint8_t *data, uint16_t data_len) { } LiPkg::LiPkg() - : sdk_pack_version_("v2.3.4"), + : sdk_pack_version_("v2.3.5"), timestamp_(0), speed_(0), error_times_(0), diff --git a/package.xml b/package.xml index b61676b..77ab8d2 100644 --- a/package.xml +++ b/package.xml @@ -1,19 +1,19 @@ ldlidar_stl_ros - 0.0.0 + 2.3.5 The ldlidar package - marketing1 + SHENZHEN LDROBOT CO., LTD. - TODO + MIT @@ -48,25 +48,37 @@ + catkin + - roscpp - sensor_msgs + + + + - roscpp - sensor_msgs + + + + - roscpp - sensor_msgs + + + + + roscpp + sensor_msgs + tf + - + - + diff --git a/scripts/ldlidar.rules b/rules/ldlidar.rules similarity index 100% rename from scripts/ldlidar.rules rename to rules/ldlidar.rules diff --git a/scripts/create_udev_rules.sh b/scripts/create_udev_rules.sh index d9c4f5a..740fc90 100644 --- a/scripts/create_udev_rules.sh +++ b/scripts/create_udev_rules.sh @@ -3,7 +3,7 @@ echo "remap the device serial port(ttyUSBX) to ldlidar" echo "ldlidar usb connection as /dev/ldlidar , check it using the command : ls -l /dev|grep ttyUSB" echo "start copy ldlidar.rules to /etc/udev/rules.d/" -sudo cp ./ldlidar.rules /etc/udev/rules.d +sudo cp `rospack find ldlidar_stl_ros`/rules/ldlidar.rules /etc/udev/rules.d/ echo " " echo "Restarting udev" echo "" diff --git a/scripts/delete_udev_rules.sh b/scripts/delete_udev_rules.sh index e296148..7e6f1a2 100644 --- a/scripts/delete_udev_rules.sh +++ b/scripts/delete_udev_rules.sh @@ -2,7 +2,7 @@ echo "delete remap the device serial port(ttyUSBX) to ldlidar" echo "sudo rm /etc/udev/rules.d/ldlidar.rules" -sudo rm /etc/udev/rules.d/ldlidar.rules +sudo rm /etc/udev/rules.d/ldlidar.rules echo " " echo "Restarting udev" echo "" diff --git a/src/publish_node/main.cpp b/src/publish_node/main.cpp index 5da05c7..1539765 100644 --- a/src/publish_node/main.cpp +++ b/src/publish_node/main.cpp @@ -21,7 +21,8 @@ #include "ros_api.h" #include "lipkg.h" -void ToLaserscanMessagePublish(ldlidar::Points2D& src, ldlidar::LiPkg* commpkg, LaserScanSetting& setting, ros::Publisher& lidarpub); +void ToLaserscanMessagePublish(ldlidar::Points2D& src, ldlidar::LiPkg* commpkg, + LaserScanSetting& setting, ros::Publisher& lidarpub); int main(int argc, char **argv) { ros::init(argc, argv, "ldldiar_publisher"); @@ -104,27 +105,33 @@ int main(int argc, char **argv) { return 0; } -void ToLaserscanMessagePublish(ldlidar::Points2D& src, ldlidar::LiPkg* commpkg, LaserScanSetting& setting, ros::Publisher& lidarpub) { +void ToLaserscanMessagePublish(ldlidar::Points2D& src, ldlidar::LiPkg* commpkg, + LaserScanSetting& setting, ros::Publisher& lidarpub) { float angle_min, angle_max, range_min, range_max, angle_increment; float scan_time; ros::Time start_scan_time; static ros::Time end_scan_time; + static bool first_scan = true; start_scan_time = ros::Time::now(); scan_time = (start_scan_time - end_scan_time).toSec(); + if (first_scan) { + first_scan = false; + end_scan_time = start_scan_time; + return; + } + // Adjust the parameters according to the demand - angle_min = ANGLE_TO_RADIAN(src.front().angle); - angle_max = ANGLE_TO_RADIAN(src.back().angle); + angle_min = 0; + angle_max = (2 * M_PI); range_min = 0.02; range_max = 12; - float spin_speed = static_cast(commpkg->GetSpeedOrigin()); - float scan_freq = static_cast(commpkg->kPointFrequence); - angle_increment = ANGLE_TO_RADIAN(spin_speed/scan_freq); + int beam_size = static_cast(src.size()); + angle_increment = (angle_max - angle_min) / (float)(beam_size -1); // Calculate the number of scanning points if (commpkg->GetSpeedOrigin() > 0) { - int beam_size = static_cast(ceil((angle_max - angle_min) / angle_increment)); sensor_msgs::LaserScan output; output.header.stamp = start_scan_time; output.header.frame_id = setting.frame_id; @@ -161,10 +168,11 @@ void ToLaserscanMessagePublish(ldlidar::Points2D& src, ldlidar::LiPkg* commpkg, } float angle = ANGLE_TO_RADIAN(dir_angle); // Lidar angle unit form degree transform to radian - int index = (int)((angle - output.angle_min) / output.angle_increment); + int index = static_cast(ceil((angle - angle_min) / angle_increment)); if (index < beam_size) { if (index < 0) { - ROS_ERROR("[ldrobot] error index: %d, beam_size: %d, angle: %f, output.angle_min: %f, output.angle_increment: %f", index, beam_size, angle, output.angle_min, output.angle_increment); + ROS_ERROR("[ldrobot] error index: %d, beam_size: %d, angle: %f, angle_min: %f, angle_increment: %f", + index, beam_size, angle, angle_min, angle_increment); } if (setting.laser_scan_dir) {