lego loam 跑镭神32线激光雷达

师弟反应镭神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(0);
    }

    if (!private_nh.getParam("scan_topic", scan_topic))
    {
        ROS_ERROR("can not get scan_topic!");
        exit(0);
    }

    g_scan_pub = n.advertise<sensor_msgs::PointCloud2>(scan_topic, 10);
    ros::Subscriber main_topic_sub = n.subscribe<sensor_msgs::PointCloud2>(main_topic, 10000, 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 0;
}

在把我的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 = 32;
extern const int Horizon_SCAN = 2000;
extern const float ang_res_x = 360.0 / float(Horizon_SCAN);
extern const float ang_res_y = 26.0 / float(N_SCAN-1);
extern const float ang_bottom = 16.5;
extern const int groundScanInd = 10; //地面的线扫条数

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

编译。

运行lego loam:

$ roslaunch lego_loam run.launch

运行上面的launch文件

$ roslaunch record_data leishen_dispatcher.launch

最后运行你的bag

$ rosbag play --clock 2019-06-21-10-27-25.bag

不要忘记--clock

就可以开始了。

原文地址:https://www.cnblogs.com/hgl0417/p/11067660.html

时间: 2024-10-19 00:02:28

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

多线激光雷达遇到的问题

多网卡多个激光雷达,可能会遇到无法通信的问题. 1.32线激光雷达数据丢失 设置网卡的属性,增加缓冲区内存. 大型数据包.传输缓冲区.接收方调整.接收缓冲区 等几个方面进行调节. 最重要的一步,重启后生效. 2.多网卡之间如何传递数据 之前用的虚拟总线,用本地回环地址 127.0.0.1 无法进行通信,因为网卡一多之后,回环地址不知道是找的哪个网卡的数据了,介于这种问题. 我们想到设置默认网关去解决.后来,发现有冲突,没有用这种方案. 最后的解决办法: 安装回环网卡: http://jingya

16线激光雷达使用

近期使用过16线激光雷达,用作障碍物检测. 驱动程序编写. 坐标系确定. 标定,x和y方向上的标定. 高度差效果不理想,可以考虑用Z值来做障碍物检测.效果还可以,当然此是对安装在车前的雷达来说的.

为什么有的程序在64位机上跑反而比32位机更慢

最近工作遇到了一个问题,原本在32位Android机上跑的好好的程序,在某些64位机上却变慢了许多.感觉很奇怪,所以google了一下原因,网上给出的原因大部分是过多使用指针.可是为什么过多使用指针就会造成程序变慢呢?结合网上的资料,和自己的理解,我认为是如下原因造成的: (1)因为64位比32位的指针大了一倍,寻址空间从2^32大幅上升到2^64,但是这也带来了额外的问题.一个指针的存储空间也变成了原来的两倍,在做指针运算时,例如int*ptr,*(ptr+5),移动距离也变为了原来的两倍.

细数激光雷达的那些类型

激光雷达是集激光.全球定位系统(GPS).和IMU(惯性测量装置)三种技术于一身的系统,相比普通雷达,激光雷达具有分辨率高,隐蔽性好.抗干扰能力更强等优势.随着科技的不断发展,激光雷达的应用越来越广泛,在机器人.无人驾驶.无人车等领域都能看到它的身影,有需求必然会有市场,随着激光雷达需求的不断增大,激光雷达的种类也变得琳琅满目,按照使用功能.探测方式.载荷平台等激光雷达可分为不同的类型. 激光雷达类型图 激光雷达按功能分类: 激光测距雷达 激光测距雷达是通过对被测物体发射激光光束,并接收该激光光

大神品牌凸显酷派核心竞争力

日前,酷派移动互联网及电商总裁祝芳浩在大神内部会议中,正式部署有关大神产品线战略计划,表明酷派新产品线大神X.N系进入中后阶段. 据透露,在大神已经正式确立的X.N.F三大主产品系列中,X.N系为新产品,主打中高端市场,定位2000+元和1500+元价位,和已经打响市场的大神F系组成三主力线将贯穿整个品牌产品链.未来,X.N系列产品将与小米,荣耀等主要竞争对手抢夺电商中高端市场. 随着大神产品线的落地,这标志着大神品牌独立运营已驶入快车道. 酷派大神的互联网基因 从小米到华为,互联网确实展现出了

《跑步该怎么跑》读书笔记

作为程序员,一定要懂怎样健身,<跑步该怎么跑>这本书对跑步做了科学的说明,很不错. 唯一的缺点是鸡汤文太多,废话太多.以下是我整理的一些内容.重点章节做了标注. 1,追求完美的跑步技术 简单就是关键. 芭蕾,舞蹈或武术等训练,都必须先学姿势,更准确的说,就是学习无数的连续姿势.一旦姿势熟练连贯,动作才会达到完美. 2,我的跑步哲学 如果你想要健康--跑吧! 如果你想要俊美--跑吧! 如果你想要聪慧--跑吧! 人类的出生,存活与成长,全在地球的重力场中,一切肢体的活动也在特定的生物力学框架下,受

激光雷达的应用领域 你都了解多少?

历经40余年的发展,激光雷达技术已从最初的激光测距技术,逐步发展了激光跟踪.激光测速.激光扫描成像.激光多普勒成像等技术,因此出现了各种不同种类的激光雷达,被广泛应用于各个领域,激光雷达在很多年前,并未被大众所熟知,直至近年来机器人和无人驾驶技术的兴起,激光雷达才逐渐进入人们的视野,在一开始激光雷达不只为机器人(包括无人驾驶)而诞生,它还被广泛应用于VR/AR.智慧交通.海洋探索和渔业资源监测.3D打印等领域. 机器人领域--帮助机器人实现自主定位导航 自主定位导航是机器人实现自主行走的必备技术

什么是激光雷达?一文带你读懂激光雷达

近年来,随着技术的进步,激光雷达的应用领域也在逐渐扩大,不仅在环保.农业.海洋和测绘等领域发挥了重要作用,在机器人.无人驾驶.智能装备.智能家居等领域也显示出良好的应用前景,再加上国家对这些高新技术的支持,我国激光雷达行业将迎来蓬勃发展. 我国激光雷达市场规模 纵观全球激光雷达市场,北美占据整个市场收入的45%左右,欧洲占据33%市场份额.据前瞻产业研究院发布的<激光雷达行业市场前瞻与投资战略规划分析报告>数据显示,随着我国经济发展,激光雷达应用领域增加,我国激光雷达市场规模将会大幅度增长.2

巨头纷纷进击人工智能,看华为小米们如何探索未来

在2016年5月底的全国科技创新大会上,华为公司创始人.总裁任正非发表了著名的"华为进入'无人区'"讲话.任正非说,华为"正在本行业逐步攻入无人区,处在无人领航.无既定规则,无人跟随的困境","已感到前途茫茫,找不到方向". 任正非又说:"从科技的角度来看,未来二.三十年人类社会将演变成一个智能社会,其深度和广度我们还想象不到."在2016年8月12日,由中国计算机学会(CCF)主办.雷锋网承办的"全球人工智能与机器