计算两帧雷达数据之间的变换矩阵

文章目录

    • package.xml
    • CMakeLists.txt
    • point_cloud_registration.cc
    • 运行结果

package.xml

<?xml version="1.0"?>
<package format="2"><name>point_cloud_registration</name><version>0.0.0</version><description>The point_cloud_registration package</description><maintainer email="xiaoqiuslam@qq.com">xiaqiuslam</maintainer><license>TODO</license><buildtool_depend>catkin</buildtool_depend><build_depend>pcl_conversions</build_depend><build_depend>pcl_ros</build_depend><build_depend>roscpp</build_depend><build_depend>sensor_msgs</build_depend><build_export_depend>pcl_conversions</build_export_depend><build_export_depend>pcl_ros</build_export_depend><build_export_depend>roscpp</build_export_depend><build_export_depend>sensor_msgs</build_export_depend><exec_depend>pcl_conversions</exec_depend><exec_depend>pcl_ros</exec_depend><exec_depend>roscpp</exec_depend><exec_depend>sensor_msgs</exec_depend><export></export>
</package>

CMakeLists.txt

cmake_minimum_required(VERSION 3.0.2)project(point_cloud_registration)add_compile_options(-std=c++11)find_package(catkin REQUIRED COMPONENTSpcl_conversionspcl_rosroscppsensor_msgs
)find_package(PCL REQUIRED QUIET)catkin_package()include_directories(
include${catkin_INCLUDE_DIRS}${PCL_INCLUDE_DIRS}
)add_executable(point_cloud_registration src/point_cloud_registration.cc)target_link_libraries(point_cloud_registration ${catkin_LIBRARIES})

point_cloud_registration.cc

#include <chrono>
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/registration/icp.h>void ScanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg);
void ConvertScan2PointCloud(const sensor_msgs::LaserScan::ConstPtr &scan_msg);
void ScanMatchWithICP(const sensor_msgs::LaserScan::ConstPtr &scan_msg);bool is_first_scan_ = true;
pcl::PointCloud<pcl::PointXYZ>::Ptr current_pointcloud_; 
pcl::PointCloud<pcl::PointXYZ>::Ptr last_pointcloud_; 
pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp_;void ScanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
{// 第一帧雷达数据if (is_first_scan_ == true){// 转换数据类型 并保存到current_pointcloud_ConvertScan2PointCloud(scan_msg);is_first_scan_ = false;}// 第二帧雷达数据else{// 数据类型转换std::chrono::steady_clock::time_point start_time = std::chrono::steady_clock::now();// 将current_pointcloud_赋值到last_pointcloud_进行保存*last_pointcloud_ = *current_pointcloud_;   // 数据类型转换 ConvertScan2PointCloud(scan_msg);// 调用ICP进行计算 雷达前后两帧间的坐标变换ScanMatchWithICP(scan_msg);}
}void ConvertScan2PointCloud(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
{pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_msg = boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>());cloud_msg->points.resize(scan_msg->ranges.size());for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i){pcl::PointXYZ &point_tmp = cloud_msg->points[i];float range = scan_msg->ranges[i];if (!std::isfinite(range))continue;if (range > scan_msg->range_min && range < scan_msg->range_max){float angle = scan_msg->angle_min + i * scan_msg->angle_increment;point_tmp.x = range * cos(angle);point_tmp.y = range * sin(angle);point_tmp.z = 0.0;}}cloud_msg->width = scan_msg->ranges.size();cloud_msg->height = 1;cloud_msg->is_dense = true;pcl_conversions::toPCL(scan_msg->header, cloud_msg->header);*current_pointcloud_ = *cloud_msg;
}void ScanMatchWithICP(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
{icp_.setInputSource(last_pointcloud_);icp_.setInputTarget(current_pointcloud_);pcl::PointCloud<pcl::PointXYZ> unused_result;icp_.align(unused_result);if (icp_.hasConverged() == false){return;}else{Eigen::Affine3f transfrom;transfrom = icp_.getFinalTransformation();float x, y, z, roll, pitch, yaw;pcl::getTranslationAndEulerAngles(transfrom, x, y, z, roll, pitch, yaw);std::cout << "transfrom: (x: " << x << ", y: " << y << ", yaw: " << yaw * 180 / M_PI << ")" << std::endl;}
}int main(int argc, char **argv)
{ros::init(argc, argv, "point_cloud_registration");ros::NodeHandle node_handle_; ros::Subscriber laser_scan_subscriber_;laser_scan_subscriber_ = node_handle_.subscribe("laser_scan", 1, &ScanCallback);current_pointcloud_ = boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>());last_pointcloud_ = boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>());ros::spin();return 0;
}

运行结果

roscore 
source devel/setup.bash && rosrun point_cloud_registration point_cloud_registration
rosbag play 1.bag 

在这里插入图片描述

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

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

mysql的trace追踪SQL工具,进行sql优化

trace是MySQL5.6版本后提供的SQL跟踪工具&#xff0c;通过使用trace可以让我们明白optimizer&#xff08;优化器&#xff09;如何选择执行计划。 注意&#xff1a;开启trace工具会影响mysql性能&#xff0c;所以只适合临时分析sql使用&#xff0c;用完之后请立即关闭。 测试数…

golang开发:goroutine在项目中的使用姿势

很多初级的Gopher在学习了goroutine之后&#xff0c;在项目中其实使用率不高&#xff0c;尤其一些跨语言过来的人&#xff0c;对并发编程理解不深入&#xff0c;可能很多人只知道go func(),或者掌控不够&#xff0c;谨慎一些&#xff0c;尽量少使用或者不使用&#xff0c;用的话…

博士推荐 | 美国知名化工企业研发主管,高分子科学与工程博士

编辑 / 木子 审核 / 朝阳 伟骅英才 伟骅英才致力于以大数据、区块链、AI人工智能等前沿技术打造开放的人力资本生态&#xff0c;用科技解决职业领域问题&#xff0c;提升行业数字化服务水平&#xff0c;提供创新型的产业与人才一体化服务的人力资源解决方案和示范平台&#x…

未来城市:探索数字孪生在智慧城市中的实际应用与价值

目录 一、引言 二、数字孪生与智慧城市的融合 三、数字孪生在智慧城市中的实际应用 1、智慧交通管理 2、智慧能源管理 3、智慧建筑管理 4、智慧城市管理 四、数字孪生在智慧城市中的价值 五、挑战与展望 六、结论 一、引言 随着科技的飞速发展&#xff0c;智慧城市已…

Windows系统安装Tomcat并结合内网穿透实现公网访问本地网页

文章目录 前言1.本地Tomcat网页搭建1.1 Tomcat安装1.2 配置环境变量1.3 环境配置1.4 Tomcat运行测试1.5 Cpolar安装和注册 2.本地网页发布2.1.Cpolar云端设置2.2 Cpolar本地设置 3.公网访问测试4.结语 前言 Tomcat作为一个拥有强大功能的轻量级服务器&#xff0c;由于其可以实…

代码讲解:如何把3D数据转换成旋转的视频?

目录 3D数据集下载 读取binvox文件 使用matplotlib创建图 动画效果 完整代码 3D数据集下载 这里以shapenet数据集为例&#xff0c;可以访问外网的可以去直接申请下载&#xff1b;我也准备了一个备份在百度网盘的数据集&#xff0c;可以参考&#xff1a; ShapeNet简介和下…

【C++庖丁解牛】实现string容器的增删查改 | string容器的基本接口使用

&#x1f4d9; 作者简介 &#xff1a;RO-BERRY &#x1f4d7; 学习方向&#xff1a;致力于C、C、数据结构、TCP/IP、数据库等等一系列知识 &#x1f4d2; 日后方向 : 偏向于CPP开发以及大数据方向&#xff0c;欢迎各位关注&#xff0c;谢谢各位的支持 目录 前言&#x1f4d6;pu…

数据结构部分

来源地址 一 数据结构 1 堆和树之间的区别 区别就在于树是没有特定顺序的&#xff0c;你需要遍历整个树才能找到特定元素&#xff1b;而堆是有序的&#xff0c;你可以直接找到最大&#xff08;或最小&#xff09;的元素。 堆&#xff1a;假设你正在开发一个任务调度系统&…

2024蓝桥杯每日一题(多路归并)

一、第一题&#xff1a;鱼塘钓鱼 解题思路&#xff1a;多路归并优先队列 首先枚举能走到的距离然后再用优先队列将最大的值累加 【Python程序代码】 from heapq import * n int(input()) a [0] list(map(int,input().split())) b [0] list(map(int,input().spli…

数据结构(九)——单链表的基本操作

&#x1f600;前言 单链表是一种常见的数据结构&#xff0c;它由一系列结点组成&#xff0c;每个结点包含数据元素和指向下一个结点的指针。在本篇文章中&#xff0c;我们将讨论单链表的基本操作&#xff0c;包括初始化、销毁、清空、求表长、按值查找、插入和删除等操作。这些…

NGINX源码安装详细配置文档

NGINX源码安装详细配置文档 一、基础Linux指令 查看nginx进程是否启动&#xff1a;ps -ef | grep nginx 关闭防火墙&#xff1a;systemctl stop firewalld 开放80端口&#xff1a;firewall-cmd --zonepublic --add-port80/tcp --permanent 关闭80端口&#xff1a;firewall-cmd …

AJAX-HTTP协议

文章目录 HTTP协议请求报文响应报文接口文档 HTTP协议 规定了浏览器发送及服务器返回内容的格式 请求报文 浏览器按照HTTP协议要求的格式&#xff0c;发送给服务器的内容 组成部分&#xff1a; 1.请求行&#xff1a;请求方法&#xff0c;URL&#xff0c;协议 2.请求头&#…