科力2D Lidar使用指南
作者: Herman Ye @Galbot @Auromix
 版本: V1.0
 测试环境: Ubuntu20.04(x86) PC 以及 Ubuntu20.04(Arm) Nvidia Orin
 更新日期: 2023/11/11
 注1: 本文内容中的硬件由 @Galbot 提供支持。
 注2: @Auromix 是一个机器人爱好者开源组织。
 注3: 本文在更新日期经过测试,确认有效。
 注4: 本文中直接引用科力官方文档的部分内容,版权为科力所有。
Quickstart Guide
1.安装及编译
# Go to your workspace src
cd ~/galbot_ws/src
# Download latest package (Warning@HermanYe: bugs exist.)
git clone https://gitee.com/keli_tech31/sdkeli_ls_udp.git
# Set permissions for directory
sudo chmod 775 -R sdkeli_ls_udp
# Install dependencies
cd ~/galbot_ws
rosdep install --ignore-src --from-path src --rosdistro noetic -y
# Build rm_msgs and galbot_ros_interfaces(Info@HermanYe: Only if you use galbot_ros and realman arm)
catkin_make --pkg rm_msgs
catkin_make --pkg galbot_ros_interfaces
# Build the workspace
catkin_make
 
2.IP配置
雷达设备的默认网络信息为:
| Device | Address | Netmask | Gateway | 
|---|---|---|---|
| Keli Lidar | 192.168.0.1 | 255.255.255.0 | 192.168.1.1 | 
若不修改IP,则只需要将本机的以太网连接信息更改为和雷达同一网段
| Device | Address | Netmask | Gateway | 
|---|---|---|---|
| My computer | 192.168.0.233 | 255.255.255.0 | 192.168.1.1 | 
通过ping进行测试
ping 192.168.0.10
 
使用上位机修改雷达IP
修改雷达IP到需要使用的网段,此处设定雷达IP为192.168.1.25 ,上位机在software_and_docs文件夹中,上位机软件的压缩包解压密码为keili2021
- 运行
帮助软件,并通过以太网扫描设备、建立连接,效果如图:

通过以太网扫描->选中IP为192.168.0.10的设备,调整设备网络参数->IP地址->更改为192.168.1.25或其他需要的值->随后在设备网络参数修改中点击网络配置->完成配置后断电重启Lidar->通过以太网连接看是否有数据返回 
注意: 本机的静态IP设置也需要随之更改。

设置本机IP
此时Lidar和本机的IP设置应当如下
| Device | Address | Netmask | Gateway | 
|---|---|---|---|
| Keli Lidar | 192.168.1.25(此前修改后的IP值) | 255.255.255.0 | 192.168.1.1 | 
| My computer | 192.168.1.233(192.168.1.xxx均可) | 255.255.255.0 | 192.168.1.1 | 
测试ping正常
通过ping进行测试,应该返回如下结果:
ping 192.168.1.25
 
PING 192.168.1.25 (192.168.1.25) 56(84) bytes of data.
64 bytes from 192.168.1.25: icmp_seq=1 ttl=128 time=0.138 ms
64 bytes from 192.168.1.25: icmp_seq=2 ttl=128 time=0.122 ms
64 bytes from 192.168.1.25: icmp_seq=3 ttl=128 time=0.183 ms
64 bytes from 192.168.1.25: icmp_seq=4 ttl=128 time=0.188 ms
 
修改Launch文件中的IP设置
# Go to your workspace src
cd ~/galbot_ws/src
# Edit config
sudo nano sudo nano /sdkeli_ls_udp/launch/sdkeli_ls1207de_udp_with_1_lidar.launch
 
将IP相关行修改为:
      <param name="hostname" type="string" value="192.168.1.25" />
 
4.运行
运行雷达节点
# Terminal 1
roslaunch sdkeli_ls_udp sdkeli_ls1207de_udp_with_1_lidar.launch 
 
查看雷达消息的可视化
# Terminal 2
rviz
 


其他有用信息
雷达参数配置
# Go to your workspace src
cd ~/galbot_ws/src
# Edit config
sudo nano /sdkeli_ls_udp/cfg/SDKeliLs.cfg
 
注意: 修改后需重新编译
官方相关文档原文和上位机软件
上位机软件的压缩包解压密码为keili2021
# Go to your workspace src
cd ~/galbot_ws/src
# Check readme and software
cd sdkeli_ls_udp/software_and_docs
ls
 
ROS消息及其格式
话题为/keli_scan,类型为sensor_msgs/LaserScan
# sensor_msgs/LaserScan 
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
float32 angle_min
float32 angle_max
float32 angle_increment
float32 time_increment
float32 scan_time
float32 range_min
float32 range_max
float32[] ranges
float32[] intensities
 
包目录
# sdkeli_ls_udp package tree
├── cfg # 配置目录
│   └── SDKeliLs.cfg # 配置文件
├── CMakeLists.txt # CMake配置
├── include # 头文件目录
│   └── sdkeli_ls_udp
│       ├── parser_base.h
│       ├── sdkeli_ls1207de_parser.h
│       ├── sdkeli_ls_common.h
│       ├── sdkeli_ls_common_udp.h
│       ├── sdkeli_ls_constants.h
│       └── sdkeli_ls_sensor_frame.h
├── launch # 启动文件
│   ├── sdkeli_ls1207de_udp_nodelet_with_1_lidar.launch
│   ├── sdkeli_ls1207de_udp_nodelet_with_2_lidars.launch
│   ├── sdkeli_ls1207de_udp_with_1_lidar.launch
│   └── sdkeli_ls1207de_udp_with_2_lidars.launch
├── meshes # 模型文件
│   └── sdkeli_ls1207de.stl
├── package.xml # 包描述
├── plugins
│   └── sdkeli_ls1207de.xml
├── README.md # 不详细的readme
├── software_and_docs # 官方原文档及上位机软件
│   ├── 使用说明书-LS2测量型激光雷达(2021年8月版).pdf
│   ├── 科力激光扫描仪ROS包使用说明.doc
│	└── ···
├── src # 代码
│   ├── parser_base.cpp
│   ├── sdkeli_ls1207de.cpp
│   ├── sdkeli_ls1207de_nodelet.cpp
│   ├── sdkeli_ls1207de_parser.cpp
│   ├── sdkeli_ls_common.cpp
│   ├── sdkeli_ls_common_udp.cpp
│   ├── sdkeli_ls_sensor_frame.cpp
│   └── style_c1.bat
└── urdf # 机器人描述文件
    ├── sdkeli_ls1207de_2.urdf.xacro
    ├── sdkeli_ls1207de.urdf.xacro
    └── sdkeli_ls_udp.urdf.xacro
 
Troubleshooting
数值转换问题
Error
将较大的整数值(比如int)转换为较小的整数类型(比如char)时,编译器可能会发出警告,因为这可能导致数据丢失或溢出,此处涉及将整数值(如165和170)转换为字符类型(char)。
/home/hermanye20/galbot_ws/src/sdkeli_ls_udp/include/sdkeli_ls_udp/sdkeli_ls_constants.h:22:95: error: narrowing conversion of ‘165’ from ‘int’ to ‘char’ [-Wnarrowing]
/home/hermanye20/galbot_ws/src/sdkeli_ls_udp/include/sdkeli_ls_udp/sdkeli_ls_constants.h:22:95: error: narrowing conversion of ‘170’ from ‘int’ to ‘char’ [-Wnarrowing]
/home/hermanye20/galbot_ws/src/sdkeli_ls_udp/include/sdkeli_ls_udp/sdkeli_ls_constants.h:23:95: error: narrowing conversion of ‘250’ from ‘int’ to ‘char’ [-Wnarrowing]
   23 | const char CMD_START_STREAM_DATA[]           = {0xFA, 0x5A, 0xA5, 0xAA, 0x00, 0x02, 0x01, 0x01};
      |                                                                                               ^
/home/hermanye20/galbot_ws/src/sdkeli_ls_udp/include/sdkeli_ls_udp/sdkeli_ls_constants.h:23:95: error: narrowing conversion of ‘165’ from ‘int’ to ‘char’ [-Wnarrowing]
/home/hermanye20/galbot_ws/src/sdkeli_ls_udp/include/sdkeli_ls_udp/sdkeli_ls_constants.h:23:95: error: narrowing conversion of ‘170’ from ‘int’ to ‘char’ [-Wnarrowing]
make[2]: *** [sdkeli_ls_udp/CMakeFiles/sdkeli_ls_udp_lib.dir/build.make:76: sdkeli_ls_udp/CMakeFiles/sdkeli_ls_udp_lib.dir/src/sdkeli_ls_common.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:8194: sdkeli_ls_udp/CMakeFiles/sdkeli_ls_udp_lib.dir/all] Error 2
make: *** [Makefile:146: all] Error 2
Invoking "make -j32 -l32" failed
 
solution
不要使用官方最新repo的代码,存在问题。尝试使用商用稳定版本。
雷达通讯建立失败问题
Error
在启动雷达节点是出现连接失败,硬件LED灯未显示6表示未建立网络通信
[ INFO] [1699696621.075139454]: sending data to '192.168.0.10' (IP : 192.168.0.10) (PORT : 2112)
[ WARN] [1699696626.079184014]: GetDataGram timeout for 5s
[ERROR] [1699696626.079250132]: SDKELI_LS - Read Error when getting datagram: 1
[ERROR] [1699696626.079360133]: close socket and CloseDevice
[ INFO] [1699696626.079401922]: sdkeli_ls_udp drvier exiting.
[ INFO] [1699696626.262384635]: sending data to '192.168.0.10' (IP : 192.168.0.10) (PORT : 2112)
^C[sdkeli_ls1207de-2] killing on exit
[robot_state_publisher-1] killing on exit
[ WARN] [1699696629.064359551]: GetDataGram timeout for 5s
[ERROR] [1699696629.064417953]: SDKELI_LS - Read Error when getting datagram: 1
[ERROR] [1699696629.064533220]: close socket and CloseDevice
[ INFO] [1699696629.064574961]: sdkeli_ls_udp drvier exiting.
^Cshutting down processing monitor...
... shutting down processing monitor complete
done
 
solution
通过win环境下上位机帮助软件修改设备IP


















