科力雷达Lidar使用指南

news2025/1/16 1:42:50

科力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配置

雷达设备的默认网络信息为:

DeviceAddressNetmaskGateway
Keli Lidar192.168.0.1255.255.255.0192.168.1.1

若不修改IP,则只需要将本机的以太网连接信息更改为和雷达同一网段

DeviceAddressNetmaskGateway
My computer192.168.0.233255.255.255.0192.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设置应当如下

DeviceAddressNetmaskGateway
Keli Lidar192.168.1.25(此前修改后的IP值)255.255.255.0192.168.1.1
My computer192.168.1.233(192.168.1.xxx均可)255.255.255.0192.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

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/1197704.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

物联网AI MicroPython学习之语法uzlib解压缩

学物联网&#xff0c;来万物简单IoT物联网&#xff01;&#xff01; uzlib 介绍 uzlib 模块解压缩用DEFLATE算法压缩的二进制数据 &#xff08;通常在zlib库和gzip存档器中使用&#xff09;&#xff0c;压缩功能尚未实现。 注意&#xff1a;解压缩前&#xff0c;应检查模块内可…

C语言——个位数为 6 且能被 3 整除但不能被 5 整除的三位自然数共有多少个,分别是哪些?

#define _CRT_SECURE_NO_WARNINGS 1#include<stdio.h> int main() {int i,j0;for(i100;i<1000;i) {if(i%106&&i%30&&i%5!0){printf("%6d",i); j;}}printf("\n一共%d个\n",j);return 0; } %6d起到美化输出格式的作用&#xff…

(一)QML加载离线地图+标记坐标点

1、实现效果 加载离线地图瓦片、鼠标拖拽、滚轮缩放在地图上固定坐标位置标注地名 &#xff08;一&#xff09;QML加载离线地图标记坐标点&#xff1a;MiniMap-mini 2、实现方法 2.1、使用工具下载离线地图 不废话&#xff0c;直接搬别人的砖&#xff0c;曰&#xff1a;他山…

jbase实现申明式事务

对有反射的语言&#xff0c;申明式事务肯定不可少。没必要没个人都try&#xff0c;catch写事务&#xff0c;写的不好的话还经常容易锁表&#xff0c;为此给框架引入申明式事务。申明式既字面意思&#xff0c;在需要事务的方法前面加一个申明&#xff0c;那么框架保证事务。 首…

比亚迪推动启动电池无铅化 车主有福了

时间过得很快&#xff0c;又到了立冬&#xff0c;意味着冬季已经开始。此时的北方已经下起了大雪&#xff0c;即便是艳阳高照的粤北山区&#xff0c;早晚也出现了较大的温差。笔者不禁想起此前做二手车时期的尴尬场面——三年以上的老车&#xff0c;尤其是没有更换过启动电池的…

38 路由的过滤器配置

3.3.断言工厂 我们在配置文件中写的断言规则只是字符串&#xff0c;这些字符串会被Predicate Factory读取并处理&#xff0c;转变为路由判断的条件 例如Path/user/**是按照路径匹配&#xff0c;这个规则是由 org.springframework.cloud.gateway.handler.predicate.PathRoute…

Python实现局部二进制算法(LBP)

1.介绍 局部二进制算法是一种用于获取图像纹理的算法。这算法可以应用于人脸识别、纹理分类、工业检测、遥感图像分析、动态纹理识别等领域。 2.示例 """ 局部二进制算法&#xff0c;计算图像纹理特征 """ import cv2 import numpy as np imp…

Java自学第9课:JSP基础及内置对象

目录&#xff1a; 目录 1 JSP基础知识架构 1 指令标识 1 Page命令 2 Including指令 3 taglib指令 2 脚本标识 1 JSP表达式 2 声明标识 3 代码片段 3 JSP注释 1 HTML注释 2 带有JSP表达式的注释 3 隐藏注释 4 动态注释 4 动作标识 1 包含文件标识 2 请求转发标…

写在 Chappyz 即将上所之前:基于 AI 技术对 Web3 营销的重新定义

前不久&#xff0c;一个叫做 Chappyz 的项目&#xff0c;其生态代币 $CHAPZ 在 Seedify、Poolz、Decubate、ChainGPT、Dao Space 等几大 IDO 平台实现了上线后几秒售罄&#xff0c;并且 Bitget、Gate.io、PancakeSwap 等几大平台也纷纷表示支持&#xff0c;并都将在 11 月 13 日…

浅析移动端车牌识别技术的工作原理及其过程

随着社会经济的发展与汽车的日益普及带来巨大的城市交通压力,在此背景下,智能交通系统成为解决这一问题的关键。而在提出发展无线智能交通系统后,作为智能交通的核心,车牌识别系统需要开始面对车牌识别移动化的现实需求。基于实现车牌识别移动化这一目标,一种基于Android移动终…

报时机器人的rasa shell执行流程分析

本文以报时机器人为载体&#xff0c;介绍了报时机器人的对话能力范围、配置文件功能和训练和运行命令&#xff0c;重点介绍了rasa shell命令启动后的程序执行过程。 一.报时机器人项目结构 1.对话能力范围 (1)能够识别欢迎语意图(greet)和拜拜意图(goodbye) (2)能够识别时间意…

运行npm install卡住不动的几种解决方案

在前端开发经常会遇到运行npm install 来安装工具包一直卡住不动&#xff0c;为此这里提供几种解决方案&#xff0c;供大家参考学习&#xff0c;不足之处还请指正。 第一种方案、首先检查npm代理&#xff0c;是否已经使用国内镜像 // 执行以下命令查看是否为国内镜像 npm con…

基于FANUC工业机器人的坐标系转换、多视角拼接与三维重建

0.简介 总体任务&#xff1a;机械臂末端安装三维相机&#xff0c;绕着工件进行拍摄&#xff0c;并在计算机中将每次拍摄的点云合并在同一个坐标系下&#xff0c;从而获得更加完整全面的点云。机械臂&#xff1a;FANAUC相机&#xff1a;梅卡曼德技术方案&#xff1a;使用相机外…

有趣的 TCP 抢带宽行为

昨天发了一篇 非技术文章&#xff0c;很多人找我讨论&#xff0c;浓缩成一句话&#xff0c;就是 “死道友而不死贫道”&#xff0c;我的简历上写着这些把戏能带来什么&#xff0c;我的 blog 上写着这么做是多么无耻&#xff0c;哈哈。 看看共享链路上如何挤占带宽&#xff1a; …

Mysql数据库 13.SQL语言 触发器

一、触发器&#xff08;操作日志表&#xff09; 1.介绍 不需要主动调用的一种储存过程&#xff0c;是一个能够完成特定过程&#xff0c;存储在数据库服务器上的SQL片段。 对当前表中数据增删改查的一种记录<日志表>&#xff0c;根据触发器自动执行&#xff0c;记录当前…

html+css+javascript打造网页内容浮动导航菜单

1需求分析 前段时间把“圳品”信息发布到网站上了&#xff0c;内容包括四大块&#xff1a; 按分布区域统计分析按产品类别统计分析按认定时间统计分析河池市“圳品”清单 导致网页很长&#xff0c;有同事反映说查看起来不是很方便&#xff0c;于是决定加上一个网页内容浮动导…

x3daudio1_7.dll怎么解决?x3daudio1_7.dll丢失的5个详细处理方法

首先&#xff0c;让我们来了解一下X3DAudio1_7.dll丢失的原因。X3DAudio1_7.dll是一个非常重要的动态链接库文件&#xff0c;它负责处理计算机中的音频输出。然而&#xff0c;由于各种原因&#xff0c;例如软件安装错误、病毒感染、系统升级等&#xff0c;我们可能会遇到X3DAud…

C语言--从键盘输入当月利润I,求应发奖金总数。

题目描述&#xff1a; 企业发放的奖金根据利润提成。利润I低于或等于100000元的&#xff0c;奖金可提成10%; 利润高于100000 元&#xff0c;低于200000元(1000001000000时&#xff0c;超过1000000元的部分按 1%提成。从键盘输入当月利润I,求应发奖金总数。 int main() {int m…

自动驾驶学习笔记(八)——路线规划

#Apollo开发者# 学习课程的传送门如下&#xff0c;当您也准备学习自动驾驶时&#xff0c;可以和我一同前往&#xff1a; 《自动驾驶新人之旅》免费课程—> 传送门 《Apollo Beta宣讲和线下沙龙》免费报名—>传送门 文章目录 前言 路线规划 路由元素 路径搜索 最优…

【C++】函数指针 ① ( 函数三要素 | 函数类型 | 函数指针类型 | 函数类型重命名 )

文章目录 一、函数类型 和 函数指针类型1、函数三要素2、函数类型3、函数指针类型4、函数类型重命名 二、代码示例 - 函数类型重命名1、代码分析2、完整代码示例 一、函数类型 和 函数指针类型 1、函数三要素 函数原型有三个重要要素 : 函数名称 : 使用 标识符 为函数命名 ; 用…