有些小车车身比较长,如果是一个激光雷达,顾前不顾后,有比较大的视野盲区,这对小车导航定位避障来说都是一个问题,比如AGV小车,

所有想在小车前后各加一个雷达,那问题是ROS的建图或者定位导航都只是支持一个雷达,这个时候就需要我们做2个雷达的融合了。

方法比较简单:我的思路是先将两个激光雷达获得的laser_scan转成point_cloud也就是点云,利用pcl库将两个点云拼接在一起,然后在把拼接后的点云重新转成laser_scan。

这样ros里面建图导航都可以用了。

关键点是要把两个激光雷达的偏移量算好,以及雷达的时间同步。代码也比较简单,贴出部分关键代码:

//时间同步

message_filters::Subscriber<sensor_msgs::PointCloud2> points_sub_left(nh, left_topic, 10);
message_filters::Subscriber<sensor_msgs::PointCloud2> points_sub_right(nh, right_topic, 10);
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> MySyncPolicy;
message_filters::Synchronizer<MySyncPolicy> sync(MySyncPolicy(100000), points_sub_left, points_sub_right);
sync.registerCallback(boost::bind(&callback, _1, _2));

g_left_right_point_pub = nh.advertise<sensor_msgs::PointCloud2>(fusion_topic, 10);

//ros回调函数,拼接点云

void callback(const sensor_msgs::PointCloud2::ConstPtr& left_input, const sensor_msgs::PointCloud2::ConstPtr& right_input)
{
pcl::PointCloud<pcl::PointXYZI>::Ptr left_local_laser(new pcl::PointCloud<pcl::PointXYZI>());
pcl::fromROSMsg(*left_input, *left_local_laser);

pcl::PointCloud<pcl::PointXYZI>::Ptr left_calibration_cloud(new pcl::PointCloud<pcl::PointXYZI>());
pcl::transformPointCloud(*left_local_laser, *left_calibration_cloud, g_left_calibration_matrix);

for(std::size_t i = 0; i < left_calibration_cloud->size(); ++i)
{
left_calibration_cloud->points[i].intensity = 64;
}

// publishCloudI(&g_left_calib_point_pub, *left_calibration_cloud);

pcl::PointCloud<pcl::PointXYZI>::Ptr right_local_laser(new pcl::PointCloud<pcl::PointXYZI>());
pcl::fromROSMsg(*right_input, *right_local_laser);

pcl::PointCloud<pcl::PointXYZI>::Ptr right_calibration_cloud(new pcl::PointCloud<pcl::PointXYZI>());
pcl::transformPointCloud(*right_local_laser, *right_calibration_cloud, g_right_calibration_matrix);
for(std::size_t i = 0; i < right_calibration_cloud->size(); ++i)
{
right_calibration_cloud->points[i].intensity = 128;
}

pcl::PointCloud<pcl::PointXYZI>::Ptr left_right_middle_calibration_cloud(new pcl::PointCloud<pcl::PointXYZI>());
*left_right_middle_calibration_cloud = *left_calibration_cloud + *right_calibration_cloud;

publishCloudI(&g_left_right_point_pub, *left_right_middle_calibration_cloud);
}

最新文章

  1. ubuntu下git安装及使用
  2. C# 对MongoDB 进行增删改查的简单操作 (转)
  3. XA事务处理
  4. Spring与Hibernate、Mybatis整合
  5. java: cannot execute binary file
  6. WPF Popup 置顶问题
  7. IOS开发—UITableView重用机制的了解
  8. AutoTile 自动拼接(二) 学习与实践
  9. Codeforce B. Polycarp and Letters
  10. UVA1374 IDA*
  11. 10种软件开发中 over-engineering 的错误套路
  12. IP负载均衡
  13. saltstack系列~第二篇
  14. codeforces 848B Rooter&#39;s Song 思维题
  15. PHP学习 Object Oriented 面向对象 OO
  16. 关于css中a标签的样式
  17. https://blog.csdn.net/u012150179/article/details/38091411
  18. Autopilot Pattern Redis
  19. Sql求和异常——对象不能从 DBNull 转换为其他类型
  20. client.HConnectionManager$HConnectionImplementation: Can&#39;t get connection to ZooKeeper: KeeperErrorCode = ConnectionLoss for /hbase

热门文章

  1. Vue-Cli 3.0 中配置高德地图
  2. java编译报错 错误: 编码GBK的不可映射字符
  3. json属性里面出现特殊字符怎么获取属性
  4. 如何在Mac上使用Netstat命令
  5. Jmeter脚本录制攻略
  6. Redis分布式缓存实现
  7. 基于appium的fixture应用之代码重构
  8. HDU 1081 To the Max 最大子矩阵(动态规划求最大连续子序列和)
  9. C# Xamarin 数据绑定入门基础
  10. Java每日一面(Part1:计算机网络)[19/10/14]