单线激光雷达(SICK)驱动安装及时空标定
创始人
2024-05-29 21:18:08
0

一、引言

1、AGV需要同时具备定位、避障与导航的功能,其中避障对于雷达本身的分辨率、精度要求并不是很高,只需要能够根据预设定的雷达扫描范围准确避开障碍物即可,故本文以TIM240(SICK激光类雷达)为例介绍实现多雷达时空标定的问题。
2、多个避障雷达可能会被安装在车体各个位置,并且不一定有重叠区域,所以通过提取特征点再进行ICP或NDT配准的方法获取相对位姿变换关系的方式不可行,由于机械结构本身已经按照设计图纸预先设置好雷达的安装位置,所以雷达之间的相对位置关系相对准确,故可以直接利用已有参数可以进行雷达空间标定,将两个雷达数据统一到同一个坐标系下进行,需要用到PCL库。
3、坐标变换实际使用过程当中确实可以用tf进行静态坐标变换,但是相比较直接手动写代码进行转换延迟较高,故采用手动根据相对位置关系进行坐标变换的方式。
4、进行时空标定步骤主要分为:(1)驱动安装及雷达参数配置(2)雷达时间同步(3)雷达空间同步(Rp+T,这里的旋转矩阵和平移矩阵的定义后文会给出)

二、整体思路与流程

1、SICK激光雷达驱动安装
新买的SICK雷达不仅需要安装驱动,还需要进配置文件修改参数才能正常工作
(1)安装驱动

mkdir -p ./sick_scan_ws
cd ./sick_scan_wsmkdir ./src
pushd ./src
git clone https://ghproxy.com/https://github.com/SICKAG/libsick_ldmrs.git
git clone https://ghproxy.com/https://github.com/SICKAG/msgpack11.git
git clone https://ghproxy.com/https://github.com/SICKAG/sick_scan_xd.git
popdmkdir -p ./build/msgpack11
pushd ./build/msgpack11
cmake -G "Unix Makefiles" -D CMAKE_CXX_FLAGS=-fPIC -D CMAKE_BUILD_TYPE=Release -D MSGPACK11_BUILD_TESTS=0 ../../src/msgpack11
make
sudo make install
popdsource /opt/ros/melodic/setup.bash # replace noetic by your ros distro
catkin_make_isolated --install --cmake-args -DROS_VERSION=1 -Wno-dev
source ./devel_isolated/setup.bash

(2)雷达配置文件修改
1)首先需要设置PC机的以太网ip端口号如:192.168.0.2
2)SICK官网下载sopas软件,在Windows端使用(用Win10系统,Win11有问题)
3)进入软件,修改登录权限为授权的用户,密码是client
在这里插入图片描述
4)修改雷达ip(与PC机同一网段即可,192.168.0.1以及Cola dialect改为cola binary格式。此处修改雷达ip是为了保证两个雷达能同时使用
在这里插入图片描述
(3)硬件组装
需要交换机、电源模块、电源线(普通的家庭供电线就可以,火线为棕灰色、地线为黄绿双色、零线为蓝色,分别对应接到电源模块的L端、FG端、N端)、供电线、网线,如下图连接示意图
在这里插入图片描述
(4)修改雷达启动文件(launch),需要创建两个启动文件,分别对应不同ip的雷达,我这里设置一个ip为192.168.0.1,一个为192.168.0.3,因为PC的ip为192.168.0.2



                                            

2、SICK激光雷达时间同步
主要使用ros官方提供的软同步方式(message_filters
使用方式如下:

ros::Publisher pointcloud_pub;
typedef message_filters::sync_policies::ApproximateTime testSyncPolicy;void callback(const sensor_msgs::PointCloud2ConstPtr &point1, const sensor_msgs::PointCloud2ConstPtr &point2)  //回调中包含多个消息
{//需要处理的内容//
}int main (int argc, char **argv)
{ros::init (argc, argv, "lidar2base");ros::NodeHandle n;pointcloud_pub = n.advertise("/scan", 1000);//发布的话题message_filters::Subscriber pointcloud1_sub(n, "/cloud1", 1);// 需要同步的topic1message_filters::Subscriber pointcloud2_sub(n, "/cloud2", 1);// 需要同步的topic2 message_filters::Synchronizer sync(testSyncPolicy(10), pointcloud1_sub, pointcloud2_sub);// 同步sync.registerCallback(boost::bind(&callback, _1, _2));ros::spin();ros::shutdown();return 0;
}

3、SICK激光雷达空间同步
主要是通过雷达之间的旋转和平移参数将两个雷达数据统一到一个坐标系下再使用PCL库对雷达数据进行融合,这里编写了相关函数

//坐标变换将激光雷达坐标系下的点转换到小车坐标系下
void transPoint(pcl::PointCloud::Ptr lidarCloud,pcl::PointCloud::Ptr carCloud,double yaw,double pitch,double roll,double x,double y,double z)
{Eigen::Matrix4f transform=Eigen::Matrix4f::Identity();Eigen::Matrix4f transformYaw;Eigen::Matrix4f transformPitch;Eigen::Matrix4f transformRoll;//航向角transformYaw<

如下图:
需求是通过上述函数将P点从激光雷达坐标系变换到车体坐标系,函数的输入分别为偏航角yaw, pitch, roll,x,y,z
在这里插入图片描述
偏航角yaw的获取方式是:以车坐标系为右手基准坐标系,大拇指指向为z轴正方向,激光雷达系为目标坐标系,顺时针旋转z轴的角度分量为yaw的值,图中x1Oy1为车体坐标系。
同理俯仰角pictch为绕y轴旋转角度分量,横滚角roll为绕x轴的分量。
平移分量(x, y, z)是激光雷达相对于车体坐标原点的x,y,z的坐标。

在这里插入图片描述4、雷达数据融合
需要将ros的PointCloud2类型数据转换为PCL数据类型,而后将PCL数据类型转为ros的LaserScan数据类型。
1)数据融合主要在SICK激光雷达时间同步这一部分的回调函数中写:

    pcl::PointCloud::Ptr colorcloud1(new pcl::PointCloud);pcl::fromROSMsg(*point1, *colorcloud1);pcl::PointCloud::Ptr colorcloud2(new pcl::PointCloud);pcl::fromROSMsg(*point2, *colorcloud2);pcl::PointCloud::Ptr output_points1(new pcl::PointCloud);pcl::PointCloud::Ptr output_points2(new pcl::PointCloud);transPoint(colorcloud1, output_points1, yaw1, pitch1, roll1, x1, y11, z1);transPoint(colorcloud2, output_points2, yaw2, pitch2, roll2, x2, y2, z2);pcl::PointCloud output = *output_points1 + *output_points2;//pcl::toROSMsg((*output_points1 + *output_points2), output);//以实时发布的方式发布sensor_msgs::LaserScan output2 = PointCloudToLaserscan(output);output2.header.frame_id = "base_link";pointcloud_pub.publish(output2);

2)PCL转LaserScan单独写了一个函数

sensor_msgs::LaserScan PointCloudToLaserscan(pcl::PointCloud& _pointcloud)
{float angle_min, angle_max, range_min, range_max, angle_increment;//需要自行调整的参数angle_min = -2.094395102;angle_max =  2.094395102;range_min = 0.05;range_max = 10;//角度分辨率,分辨率越小,转换后的误差越小angle_increment = 0.0174444444;//计算扫描点个数unsigned int beam_size = ceil((angle_max - angle_min) / angle_increment);sensor_msgs::LaserScan output;output.header.stamp = ros::Time::now();output.header.frame_id = "base_link";output.angle_min = angle_min;output.angle_max = angle_max;output.range_min = range_min;output.range_max = range_max;output.angle_increment = angle_increment;output.time_increment = 0.0;output.scan_time = 0.0;//先将所有数据用nan填充output.ranges.assign(beam_size, std::numeric_limits::quiet_NaN());//output.intensities.assign(beam_size, std::numeric_limits::quiet_NaN());for (auto point : _pointcloud.points){float range = hypot(point.x, point.y);float angle = atan2(point.y, point.x);int index = (int)((angle - output.angle_min) / output.angle_increment);if (index >= 0 && index < beam_size){//如果当前内容为nan,则直接赋值if (isnan(output.ranges[index])){output.ranges[index] = range;}//否则,只有距离小于当前值时,才可以重新赋值else{if (range < output.ranges[index]){output.ranges[index] = range;}}//output.intensities[index] = point.intensity;}}return output;
}

5、创建启动脚本
首先启动两个雷达,其次启动坐标转换的脚本,即可实现两个雷达的时空同步

#!/bin/bash
gnome-terminal --tab -- bash -c "roslaunch sick_scan sick_tim_240_1.launch"
sleep 1s
gnome-terminal --tab -- bash -c "roslaunch sick_scan sick_tim_240_2.launch "
sleep 2s
gnome-terminal --tab -- bash -c "source /home/lixushi/catkin_ws/devel/setup.bash; roslaunch lidar2base lidar2base.launch"

如下图为雷达实际摆放位置
在这里插入图片描述

转换前的点云图
在这里插入图片描述
转换后的点云图
在这里插入图片描述

三、参考文献

[1] https://blog.csdn.net/m0_68312479/article/details/128266483
[2] https://blog.csdn.net/hltt3838/article/details/123067620
[3] https://blog.csdn.net/m0_68312479/article/details/128266483
[4] https://adamshan.blog.csdn.net/article/details/105930565?spm=1001.2014.3001.5502
[5] https://mp.weixin.qq.com/s?__biz=MzU1NjEwMTY0Mw==&mid=2247556040&idx=1&sn=fa1f7cc63f7aeeaed69242add86efd75&chksm=fbc862acccbfebba12fd29cef32b7a34ac296f54e8ef6f19485aff81ebddd794a3364419c90b&scene=27

相关内容

热门资讯

122.(leaflet篇)l... 听老人家说:多看美女会长寿 地图之家总目录(订阅之前建议先查看该博客) 文章末尾处提供保证可运行...
育碧GDC2018程序化大世界... 1.传统手动绘制森林的问题 采用手动绘制的方法的话,每次迭代地形都要手动再绘制森林。这...
育碧GDC2018程序化大世界... 1.传统手动绘制森林的问题 采用手动绘制的方法的话,每次迭代地形都要手动再绘制森林。这...
Vue使用pdf-lib为文件... 之前也写过两篇预览pdf的,但是没有加水印,这是链接:Vu...
PyQt5数据库开发1 4.1... 文章目录 前言 步骤/方法 1 使用windows身份登录 2 启用混合登录模式 3 允许远程连接服...
Android studio ... 解决 Android studio 出现“The emulator process for AVD ...
Linux基础命令大全(上) ♥️作者:小刘在C站 ♥️个人主页:小刘主页 ♥️每天分享云计算网络运维...
再谈解决“因为文件包含病毒或潜... 前面出了一篇博文专门来解决“因为文件包含病毒或潜在的垃圾软件”的问题,其中第二种方法有...
南京邮电大学通达学院2023c... 题目展示 一.问题描述 实验题目1 定义一个学生类,其中包括如下内容: (1)私有数据成员 ①年龄 ...
PageObject 六大原则 PageObject六大原则: 1.封装服务的方法 2.不要暴露页面的细节 3.通过r...
【Linux网络编程】01:S... Socket多进程 OVERVIEWSocket多进程1.Server2.Client3.bug&...
数据结构刷题(二十五):122... 1.122. 买卖股票的最佳时机 II思路:贪心。把利润分解为每天为单位的维度,然后收...
浏览器事件循环 事件循环 浏览器的进程模型 何为进程? 程序运行需要有它自己专属的内存空间࿰...
8个免费图片/照片压缩工具帮您... 继续查看一些最好的图像压缩工具,以提升用户体验和存储空间以及网站使用支持。 无数图像压...
计算机二级Python备考(2... 目录  一、选择题 1.在Python语言中: 2.知识点 二、基本操作题 1. j...
端电压 相电压 线电压 记得刚接触矢量控制的时候,拿到板子,就赶紧去测各种波形,结...
如何使用Python检测和识别... 车牌检测与识别技术用途广泛,可以用于道路系统、无票停车场、车辆门禁等。这项技术结合了计...
带环链表详解 目录 一、什么是环形链表 二、判断是否为环形链表 2.1 具体题目 2.2 具体思路 2.3 思路的...
【C语言进阶:刨根究底字符串函... 本节重点内容: 深入理解strcpy函数的使用学会strcpy函数的模拟实现⚡strc...
Django web开发(一)... 文章目录前端开发1.快速开发网站2.标签2.1 编码2.2 title2.3 标题2.4 div和s...