师弟反应镭神32线激光雷达(32C)录制的数据包不能跑lego loam,这里就总结一下。

首先lego loam默认的接受的topic name是velodyne_points,点云的frame_id是velodyne,镭神驱动发布的topic name为point_raw,frame_id为world这里需要写一个程序转一下:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "sensor_msgs/PointCloud2.h"
#include <string> #include <sstream> /**
* This tutorial demonstrates simple sending of messages over the ROS system.
*/ static ros::Publisher g_scan_pub; static void main_topic_callback(const sensor_msgs::PointCloud2::ConstPtr& input)
{
sensor_msgs::PointCloud2 msg = *input;
msg.header.frame_id = "velodyne";
g_scan_pub.publish(msg);
} int main(int argc, char *argv[])
{
/**
* The ros::init() function needs to see argc and argv so that it can perform
* any ROS arguments and name remapping that were provided at the command line.
* For programmatic remappings you can use a different version of init() which takes
* remappings directly, but for most command-line programs, passing argc and argv is
* the easiest way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "trans_leishen_velodyne"); /**
* NodeHandle is the main access point to communications with the ROS system.
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
ros::NodeHandle private_nh("~");
ros::NodeHandle n; /**
* The advertise() function is how you tell ROS that you want to
* publish on a given topic name. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. After this advertise() call is made, the master
* node will notify anyone who is trying to subscribe to this topic name,
* and they will in turn negotiate a peer-to-peer connection with this
* node. advertise() returns a Publisher object which allows you to
* publish messages on that topic through a call to publish(). Once
* all copies of the returned Publisher object are destroyed, the topic
* will be automatically unadvertised.
*
* The second parameter to advertise() is the size of the message queue
* used for publishing messages. If messages are published more quickly
* than we can send them, the number here specifies how many messages to
* buffer up before throwing some away.
*/ std::string main_topic;
std::string scan_topic; if (!private_nh.getParam("main_topic", main_topic))
{
ROS_ERROR("can not get main_topic!");
exit();
} if (!private_nh.getParam("scan_topic", scan_topic))
{
ROS_ERROR("can not get scan_topic!");
exit();
} g_scan_pub = n.advertise<sensor_msgs::PointCloud2>(scan_topic, );
ros::Subscriber main_topic_sub = n.subscribe<sensor_msgs::PointCloud2>(main_topic, , main_topic_callback); /**
* A count of how many messages we have sent. This is used to create
* a unique string for each message.
*/
ros::spin(); return ;
}

在把我的launch文件(leishen_dispatcher.launch)也贴出来:

<launch>
<arg name="scan_topic_name" default="velodyne_points" />
<arg name="main_topic_name" default="point_raw" /> <node pkg="record_gnss_pc" name="trans_leishen_velodyne" type="trans_leishen_velodyne" output="screen">
<param name="scan_topic" value="$(arg scan_topic_name)" />
<param name="main_topic" value="$(arg main_topic_name)" />
</node>
</launch>

在将代码lego loam中的utility.h文件中添加的镭神32C的配置文件(激光雷达扫描频率分别为5Hz与10Hz)也贴一下:

// LeiShen-32C-5Hz
// extern const int N_SCAN = 32;
// extern const int Horizon_SCAN = 4000;
// extern const float ang_res_x = 360.0 / float(Horizon_SCAN);
// extern const float ang_res_y = 26 / float(N_SCAN-1);
// extern const float ang_bottom = 16.5;
// extern const int groundScanInd = 10; //地面的线扫条数 // LeiShen-32C-10Hz
extern const int N_SCAN = ;
extern const int Horizon_SCAN = ;
extern const float ang_res_x = 360.0 / float(Horizon_SCAN);
extern const float ang_res_y = 26.0 / float(N_SCAN-);
extern const float ang_bottom = 16.5;
extern const int groundScanInd = ; //地面的线扫条数

最后把imageProjection.cpp中159行的注释删除,程序部分调整完毕。

编译。

运行lego loam:

$ roslaunch lego_loam run.launch

运行上面的launch文件

$ roslaunch record_data leishen_dispatcher.launch

最后运行你的bag

$ rosbag play --clock -----.bag

不要忘记--clock

就可以开始了。

lego loam 跑镭神32线激光雷达的更多相关文章

  1. 使用velodyne16线激光雷达跑loam-velodyne

    一.velodyne-VLP16使用教程 推荐网址: http://blog.csdn.net/littlethunder/article/details/51920681 https://www.c ...

  2. 镭神激光雷达对于Autoware的适配

    1. 前言 我们的自动驾驶采用镭神激光雷达,在使用Autoware的时候,需要对镭神激光雷达的底层驱动,进行一些改变以适配Autoware. 2. 修改 (1)首先修改lslidar_c32.laun ...

  3. 使用ros_driver运行velodyne16线激光雷达

    一.使用ros_driver运行VLP16 推荐网址: http://blog.csdn.net/littlethunder/article/details/51920681 https://www. ...

  4. Lidar激光雷达市场

    Lidar激光雷达市场 近年来,激光雷达技术在飞速发展,从一开始的激光测距技术,逐步发展了激光测速.激光扫描成像.激光多普勒成像等技术,如今在无人驾驶.AGV.机器人等领域已相继出现激光雷达的身影. ...

  5. 阿里巴巴AI Lab成立两年,都做了些什么?

    https://mp.weixin.qq.com/s/trkCGvpW6aCgnFwLxrGmvQ 撰稿 & 整理|Debra 编辑|Debra 导读:在 2018 云栖人工智能峰会上,阿里巴 ...

  6. 激光雷达 LOAM 论文 解析

    转自:https://blog.csdn.net/hltt3838/article/details/109261334 固态激光雷达的一段视频:https://v.qq.com/x/page/a078 ...

  7. AD19新功能之跟随走线

    跟随走线 AD19新增跟随走线,比如需要按照特定的轨迹进行走线,比如要绕着一个圆进行走线,或者靠着边框走线,普通模式下的效果如下图所示,线会跟着指针跑: 在走线模式下,按住 shift + f ,然后 ...

  8. TOF摄像机可以替代Flash激光雷达吗?

    TOF摄像机可以替代Flash激光雷达吗? 一.基于ToF技术的Flash激光雷达 基本成像原理上ToF Camera与LiDAR相同,都采用飞行时间测距技术(包括利用APD或SPAD的直接测距法,和 ...

  9. 漫谈 SLAM 技术(上)

    欢迎大家前往腾讯云社区,获取更多腾讯海量技术实践干货哦~ 作者:解洪文 导语 随着最近几年机器人.无人机.无人驾驶.VR/AR的火爆,SLAM技术也为大家熟知,被认为是这些领域的关键技术之一.本文对S ...

随机推荐

  1. SQL SERVER 数据库授权指定用户

    在查询分析器下运行以下语句即可: GO USE [master] GO ALTER AUTHORIZATION ON DATABASE::[数据库名] TO [用户名] GO

  2. 诚聘.NET架构师、高级开发工程师(2019年8月29日发布)

    招聘单位是ABP架构设计交流群(134710707)群主阳铭所在的公司 公司简介 七二四科技有限公司成立于2015年,成立之初便由金茂资本按估值2亿投资2200万,进行“健康724”平台搭建,2017 ...

  3. 帝国CMS标签【操作类型】说明详解

    看标签的参数时候,一般最后一个参数是操作类型说明,可是后面写的是:"操作类型说明 具体看操作类型说明", 这个操作类型说明在什么地方看啊 操作类型 说明 操作类型 说明 0 各栏目 ...

  4. 如何让Python爬虫一天抓取100万张网页

    前言 文的文字及图片来源于网络,仅供学习.交流使用,不具有任何商业用途,版权归原作者所有,如有问题请及时联系我们以作处理. 作者: 王平 源自:猿人学Python PS:如有需要Python学习资料的 ...

  5. HashMap、ConcurrentHashMap解析

    一.HashMap分析 在JDK1.8之前,hashMap由数组+链表组成,1.8之后,对hashMap进行了一些修改,最大的不同就是利用了红黑树,所以其由数组+链表+红黑树组成.查找时,根据hash ...

  6. DesignPattern系列__08UML相关知识

    前言 现在,很少有人和90年代一样,自己去实现一个软件的各个方面,也就是说,在工作中,和人沟通是必备的技能.那么,作为一枚码农,如何和他人沟通呢?这就要依靠本文的主题了--UML. 简介 UML--U ...

  7. HTML中html元素的lang属性的说明

    HTML中html元素的lang属性的说明 我在刚开始学习HTML的时候,关于基本的HTML格式中有一点不明白的地方,基本格式如下 <!DOCTYPE html> <html lan ...

  8. js中for循环的研究

    转自:http://blog.csdn.net/lushuaiyin/article/details/8541500 <html> <body> <b><ce ...

  9. Web安全攻防笔记-SQL注入

    information_schema(MySQL5.0版本之后,MySQL数据库默认存放一个information_schema数据库) information_schema的三个表: SCHEMAT ...

  10. [b0042] python 归纳 (二七)_gui_tkinter_基本使用

    # -*- coding: utf-8 -*- """ 学习 Tkinter画图基本控件使用 逻辑: 放几个 输入控件.点击按钮,将输入控件内容打印出来 使用: 1. 创 ...