将镭神C32激光雷达的PointXYZ数据转化为PointXYZIR格式 - 附代码

news2024/12/29 1:56:54

之前遇到过“镭神32线激光雷达ROS下运行fromRosMsg()报错 Failed to find match for field “intensity“ 问题”,
当时确定了是镭神C32雷达缺少相应字段,并记录博客【学习记录】镭神32线激光雷达ROS下运行fromRosMsg()报错 Failed to find match for field “intensity“ 问题。

这次写了一个ros的节点代码,接受原始雷达数据,并转化为相应格式。
完整代码:https://github.com/LarryDong/lslidar_PointXYZ2PointXYZIR
说明:是另写了一个节点,接受雷达发出的原始数据,再赋予ring字段的信息,然后再发布带有这个字段的点云。
但原始并没有包括intensity字段,这个信息是丢失的,所以intensity我就瞎补了一个0,至少保证了格式正确。

基本原理

计算每个点对应的角度,看距离激光雷达定义的哪条ring最接近。
如何判断最接近?计算定义的两条ring平均值,如果在左右两个平均值之间,则认为是这个ring。

在这里插入图片描述
由于镭神32线雷达有两种角度模式,左边这种均匀分布,直接将角度近似取整就可以,比较简单。但右侧这种不均匀分布的,就需要按照手册给出的角度信息去解算到底属于哪根。

代码说明

首先列出雷达定义的角度,并计算与上一个/下一个线束的平均值。

const vector<float> g_ring_angle = {-18, -15, -12, -10, -8, -7, -6, -5,
                              -4, -3.33, -3, -2.66, -2.33, -2, -1.66, -1.33,
                              -1, -0.66, -0.33, 0, 0.33, 0.66, 1, 1.33, 
                              1.66, 2, 3, 4, 6, 8, 11, 14};   // ring angles defined by leishen
vector<float> g_angle_range;                                  // define a range between each ring angle.

void initRingAngleRange(void){
    // calculate angle range
    assert(RING_NUMBER==g_ring_angle.size());
    g_angle_range.push_back(-100);            // assign a very large value
    for(int i=0; i<RING_NUMBER-1; ++i){
        float middle_value = (g_ring_angle[i] + g_ring_angle[i + 1]) / 2;   // calculate the average value between two ring.
        g_angle_range.push_back(middle_value);
    }
    g_angle_range.push_back(100);
}

然后计算实际角度,并赋予线束id即可:

void lidarCallback(const sensor_msgs::PointCloud2ConstPtr &msg_pc){
    pcl::PointCloud<pcl::PointXYZ> pc;
    pcl::PointCloud<myPointXYZIR> pc_new;
    pcl::fromROSMsg(*msg_pc, pc);
    // convert to PointXYZIR.
    pc_new.points.reserve(pc.points.size());
    myPointXYZIR pt_new;
    for(const pcl::PointXYZ& p : pc.points){
        float angle = atan(p.z / sqrt(p.x * p.x + p.y * p.y)) * 180 / M_PI;
        if(std::isnan(angle))           // remove nan point.
            continue;
        // int scanID = int(angle + 17);           // 对于1°分辨率的雷达,直接用这行指令就可以了,不需要计算下面的不均匀分布角度。
        // for 0.33 degree mode.
        int scanID = -1;
        for(int i=0; i<RING_NUMBER; ++i){
            if(angle > g_angle_range[i] && angle <= g_angle_range[i+1]){
                scanID = i;
                break;
            }
        }
        pt_new.x = p.x;
        pt_new.y = p.y;
        pt_new.z = p.z;
        pt_new.intensity = 0;       // intensity is not used.
        pt_new.ring = scanID;
        pc_new.points.push_back(pt_new);
    }
    sensor_msgs::PointCloud2 msg_pc_new;
    pcl::toROSMsg(pc_new, msg_pc_new);
    msg_pc_new.header.frame_id = "laser_link";
    msg_pc_new.header.stamp = msg_pc->header.stamp;
    g_pub_pc.publish(msg_pc_new);
    ROS_INFO("Published new pointcloud.");
 }

踩坑记录

  • 一开始以为直接将雷达设置为1°模式扫描就可以了,结果发现精度不正常。问了客服才知道1°模式和0.33°模式不能调整。所以无奈,只能再重写这个转换代码。但还行,算的挺对。
  • rviz中PointCloud2的intensity选项,点击后会出现一个channel,还包括XYZ以及intensity等,一开始没搞明白啥意思,说明如下:
  • About RViz: If you open a PointCloud2 display and select the “Intensity” color transformer, you can select a channel to display. This doesn’t have to be intensity, it can actually be any channel of your point cloud. If you leave “autocompute intensity bounds” checked, it will compute the min + max for each point cloud separately and scale the color spectrum to that range. If you disable the check box, you can enter min + max intensity manually (good if the min/max varies a lot between point clouds and you want the colors to be consistent between point clouds).

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

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

相关文章

如何正确使用chatgpt,让chatgpt回答优质内容?

我们以chatgpt写一篇文章为例。大家都知道&#xff0c;如果直接让chatgpt写某篇文章&#xff0c;他的回答总是简洁明了的&#xff0c;因为它定位就是聊天&#xff0c;而不是会像“舔狗”一样写一篇小作文。 并且他的回答&#xff0c;总是固定格式的&#xff0c;只要稍微了解ch…

Kubernetes02:知识图谱

Kubernetes01&#xff1a;知识图谱 MESOS APACHE 分布式资源管理框架 2019-5 Twitter 》 Kubernetes Docker Swarm 2019-07 阿里云宣布 Docker Swarm 剔除 Kubernetes Google 10年容器化基础架构 borg Go语言 Borg 特点 轻量级&#xff1a;消耗资源小 开源 弹性伸缩 负载均…

根据mysql的sql文件逆向生成powerdesigner的pdm文件

背景 我们在软件项目中最基本的组成部分就是数据库&#xff0c;那么在有数据库文件的情况下如何将库表逆向生成powerdesigner的设计文件呢&#xff1f; 文字步骤 打开powerdesigner软件&#xff0c;然后选择 File ->ReverseEngineer ->Database &#xff08;1&#x…

OnlyOffice本地部署实现Excel预览(docker安装)

下载onlyoffice镜像 docker pull onlyoffice/documentserver 如果下载不了 可以尝试添加镜像 /etc/docker daemon.json文件内 添加一行 {“registry-mirrors”: [“http://f1361db2.m.daocloud.io”]} 启动镜像 &#xff08;第一个17315表示onlyoffice服务对外的端口号&…

[AUTOSAR][Fls模块] Flash Driver Module

Flash Driver Module--jianqiang.xue一、 简介二、 措施方式一&#xff1a;将FLASH操作程序作为Bootloader组件的一部分固化在存储器中方式二&#xff1a;通过通讯口将该部分代码从上位机下载到指定的RAM方式三&#xff1a;将Flash功能函数作为数据运行(推荐&#xff01;&#…

23种设计模式介绍(Python示例讲解)

文章目录一、概述二、设计模式七种原则三、设计模式示例讲解1&#xff09;创建型模式1、工厂模式&#xff08;Factory Method&#xff09;【1】简单工厂模式&#xff08;不属于GOF设计模式之一&#xff09;【2】工厂方法模式2、抽象工厂模式&#xff08;AbstractFactory&#x…

Python抽奖系统

#免费源码见文末公众号# 抽奖系统① def choujiang1():def write():with open(d:\\抽奖系统\\抽奖1.1.pickle,rb) as file:lst1pickle.load(file)namevar1.get()if name not in lst1 and name!录入成功&#xff01; and name!录入失败&#xff01; and name!:lst1.append(name)…

基于springboot+vue的便利店库存管理系统

基于springbootvue的便利店库存管理系统 ✌全网粉丝20W,csdn特邀作者、博客专家、CSDN新星计划导师、java领域优质创作者,博客之星、掘金/华为云/阿里云/InfoQ等平台优质作者、专注于Java技术领域和毕业项目实战✌ &#x1f345;文末获取项目下载方式&#x1f345; 一、项目背景…

C++面向对象(上)

文章目录前言1.面向过程和面向对象初步认识2.引入类的概念1.概念与用法2.类的访问限定符及封装3.类的作用域和实例化4.类的大小计算8.this指针3.总结前言 本文将对C面向对象进行初步介绍&#xff0c;引入类和对象的概念。围绕类和对象介绍一些基础知识&#xff0c;为以后深入学…

【数据结构】————栈

文章目录前言栈是什么&#xff0c;栈的特点实现栈的基本操作栈的相关操作声明1.创建栈2.对栈进行初始化3.销毁栈4.判断栈是否为空5.压栈操作6.删除栈顶元素7.取出栈顶元素8.计算栈内存放多少个数据总结前言 本文主要讲述特殊的线性表——栈&#xff1a; 栈是什么&#xff0c;栈…

学生信息管理系统(通讯录)----------通俗易懂、附源码、C语言实现

绪论&#xff1a; 本篇文章使结构体章节后的习题&#xff0c;如果你对C语言有问题&#xff0c;或者结构体有什么问题不妨看看我之前所写的文章&#xff08;章回体&#xff09;,对于文件管理和内存分配问题我将在后面补上&#xff0c;对于这个学生信息管理系统我用了多种方法和…

五【Spring】控制反转(IOC)

目录一 Ioc控制反转1.1 概述1.2 依赖注入二 传统依赖的问题2.1 在传统的项目中三 引入Spring解决3.1 Spring配置文件中Bean属性3.2 Bean的作用域3.3 项目案例四 基于xml的依赖注入&#xff08;注意有参 无参的构建&#xff09;4.1 设置注入4.2 构造注入&#xff08;依赖有参构造…

【Java面试总结】MySQL篇·优化篇

【Java面试总结】MySQL篇SQL优化篇1.该如何优化MySQL的查询&#xff1f;2.怎样插入数据才能更高效&#xff1f;3.表中包含几千万条数据该怎么办&#xff1f;4.MySQL的慢查询优化有了解吗&#xff1f;5.说一说你对explain的了解6.explain你一般关注什么&#xff1f;1.该如何优化…

【Linux】网络编程 - Socket套接字/基于UDP的网络通信

目录 一.套接字 1.什么是套接字/Socket套接字 2.套接字的分类 3.Socket套接字的常见API 二.网络字节序 1.什么是网络字节序 2.网络字节序和主机字节序的转换接口 三.IP地址形式上的转换 四.客户端的套接字不由程序员bind 1.为什么客户端套接字不能由程序员bind 2.OS…

【题外话】如何拯救小米11Pro这款工业垃圾

1 背景媳妇用小米11Pro手机&#xff0c;某日不慎摔落&#xff0c;幸好屏幕未碎&#xff0c;然而WiFi却怎样都无法打开&#xff0c;初以为是系统死机&#xff0c;几天依旧故障无法使用。现在的手机没有WiFi功能&#xff0c;就无法刷抖音、看视频&#xff0c;就是鸡肋了。后抽空去…

全栈之路-前端篇 | 第三讲.基础前置知识【前端标准与研发工具】学习笔记

欢迎关注「全栈工程师修炼指南」公众号点击 &#x1f447; 下方卡片 即可关注我哟!设为「星标⭐」每天带你 基础入门 到 进阶实践 再到 放弃学习&#xff01;涉及 企业运维、网络安全、应用开发、物联网、人工智能、大数据 学习知识“ 花开堪折直须折&#xff0c;莫待无花空折…

【2.19】算法题2:贪心算法、动态规划、分治

题目&#xff1a;给你一个整数数组 nums &#xff0c;请你找出一个具有最大和的连续子数组&#xff08;子数组最少包含一个元素&#xff09;&#xff0c;返回其最大和。子数组 是数组中的一个连续部分。方法一&#xff1a;贪心算法原理&#xff1a;若当前指针所指元素之前的和小…

学生和老师-课后程序(JAVA基础案例教程-黑马程序员编著-第四章-课后作业)

【案例4-4】学生和老师 【案例介绍】 1.案例描述 在班级中上课时&#xff0c;老师在讲台上讲课&#xff0c;偶有提问&#xff0c;会点名学生回答问题。虽然老师和学生都在讲话&#xff0c;但讲话的具体内容却不相同。本案例要求使用抽象类的知识编写一个程序实现老师上课的情…

Allegro如何快速清除多余的规则设置操作指导

Allegro如何快速清除多余的规则设置操作指导 在用Allegro做PCB设计的时候,会给PCB设置一些规则,在PCB设计完成之后,可能会有一些没有使用到的规则,如下图 Physical规则中的45OHM的规则是多余的 单独某个规则可以直接在规则管理器中删除,如果比较多可以用下面方法批量删除…

真实景观渲染技巧【Three.js】

受到一些很棒的 three.js 演示、与 covid 相关的旅行禁令以及可能在 pinterest 上花太多时间看美丽的旅行照片的启发——我开始看看我是否可以使用 three.js 和r3f在浏览器中渲染一个令人信服的风景场景。 推荐&#xff1a;将 NSDT场景编辑器 加入你的3D开发工具链。 在过去一个…