【激光雷达】velodyne VLP-16线激光雷达驱动程序、相位锁、时钟同步测试总结

目录

1、velodyne VLP-16线激光测试参考:

2、测试目的:

3、测试结果:

4、编写的测试代码

1、velodyne VLP-16线激光测试参考:
源码地址:

https://github.com/ros-drivers/velodyne

多线激光使用、建图总结见:

https://blog.youkuaiyun.com/xingdou520/article/details/85098314

2、测试目的:
1、测试velodyneROS驱动程序的执行过程,数据流向;

2、确认pub的数据格式,时间戳问题;

3、每一场数据包含的激光测量的具体角度问题确认。

4、点云格式确认,是否可以自定义点云格式,从而减小数据拷贝造成的时间、资源浪费。

5、测试GPS和激光时间同步方式。

6、测试激光传感器相位锁功能:GPS-PPS信号控制激光内部电机相位;

3、测试结果:
1、velodyne的驱动程序使用ROS的nodelet方式实现,可以实现多节点之间数据pub的时候零拷贝,减少数据拷贝造成的时间浪费。

2、velodyne_driver每次pub一场数据的时候,每场数据的起始角度都不一样(见图中start angle:)。

3、每一场数据超过360度,在363度左右(见图中spin angle:)。

4、velodyne_driver驱动程序,每一场数据包含76个UDP数据包(udp数据包1248字节,刨除42字节,剩余velodynePacket.msg每个数据包1206字节数据),相邻数据包之间激光的角度为:4.75-4.81度。每个包间隔1.327ms左右,合起来刚好100ms一场数据。每次读取76个完整数据包后pub一次数据(velodyneSacn.msg),

5、驱动程序发布数据的时间戳是激光传感器传上来的最后一包的数据的时候,ROS给数据添加的时间戳。

/** @brief Get one velodyne packet. */
int InputSocket::getPacket(velodyne_msgs::VelodynePacket *pkt, const double time_offset)
{
    double time1 = ros::Time::now().toSec();
 
 
    UDP方式读取一包数据
 
    double time2 = ros::Time::now().toSec();
    pkt->stamp = ros::Time((time2 + time1) / 2.0 + time_offset);  //时间戳
}


6、velodyne_pointcloud包作用,订阅velodyneSacn.msg,并根据标定文件将原始数据转为sensor_msgs::PointCloud2数据发布出去。

1、定义点云输出格式:
output_ =
      node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
2、转换点云消息为sensor_msgs::PointCloud2,并发布点云消息:
 
  /** @brief Callback for raw scan messages. */
  void Convert::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
  {
    if (output_.getNumSubscribers() == 0)         // no one listening?
      return;                                     // avoid much work
 
    // allocate a point cloud with same time and frame ID as raw data
    velodyne_rawdata::VPointCloud::Ptr
      outMsg(new velodyne_rawdata::VPointCloud());
    // outMsg's header is a pcl::PCLHeader, convert it before stamp assignment
    outMsg->header.stamp = pcl_conversions::toPCL(scanMsg->header).stamp;
    outMsg->header.frame_id = scanMsg->header.frame_id;
    outMsg->height = 1;
    // process each packet provided by the driver
    for (size_t i = 0; i < scanMsg->packets.size(); ++i)
      {
        data_->unpack(scanMsg->packets[i]
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值